Skip to content

Commit db974ea

Browse files
doisygGuillaume DoisySteveMacenskiJames Ward
authored
RPP Dexory tweaks (#4140)
* RPP Dexory tweaks Signed-off-by: Guillaume Doisy <[email protected]> * Update nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp Signed-off-by: Steve Macenski <[email protected]> * projectCarrotPastGoal test Signed-off-by: Guillaume Doisy <[email protected]> * Use circleSegmentIntersection when projecting past end of path This guarantees that the look ahead distance is maintained Signed-off-by: James Ward <[email protected]> * lint Signed-off-by: Guillaume Doisy <[email protected]> --------- Signed-off-by: Guillaume Doisy <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: James Ward <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Steve Macenski <[email protected]> Co-authored-by: James Ward <[email protected]>
1 parent 53f1f42 commit db974ea

File tree

10 files changed

+218
-31
lines changed

10 files changed

+218
-31
lines changed

nav2_regulated_pure_pursuit_controller/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.5)
22
project(nav2_regulated_pure_pursuit_controller)
33

44
find_package(ament_cmake REQUIRED)
5+
find_package(nav2_amcl REQUIRED)
56
find_package(nav2_common REQUIRED)
67
find_package(nav2_core REQUIRED)
78
find_package(nav2_costmap_2d REQUIRED)
@@ -26,6 +27,7 @@ set(dependencies
2627
nav2_costmap_2d
2728
pluginlib
2829
nav_msgs
30+
nav2_amcl
2931
nav2_util
3032
nav2_core
3133
tf2

nav2_regulated_pure_pursuit_controller/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@ Note: The maximum allowed time to collision is thresholded by the lookahead poin
9090
| `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. |
9191
| `max_angular_accel` | Maximum allowable angular acceleration while rotating to heading, if enabled |
9292
| `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. |
93+
| `interpolate_curvature_after_goal` | Needs use_fixed_curvature_lookahead to be true. Interpolate a carrot after the goal dedicated to the curvate calculation (to avoid oscilaltions at the end of the path) |
9394

9495
Example fully-described XML with default parameter values:
9596

@@ -137,6 +138,7 @@ controller_server:
137138
rotate_to_heading_min_angle: 0.785
138139
max_angular_accel: 3.2
139140
max_robot_pose_search_dist: 10.0
141+
interpolate_curvature_after_goal: false
140142
cost_scaling_dist: 0.3
141143
cost_scaling_gain: 1.0
142144
inflation_cost_scaling_factor: 3.0

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,7 @@ struct Parameters
5656
double rotate_to_heading_min_angle;
5757
bool allow_reversing;
5858
double max_robot_pose_search_dist;
59+
bool interpolate_curvature_after_goal;
5960
bool use_collision_detection;
6061
double transform_tolerance;
6162
};

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,11 +58,12 @@ class PathHandler
5858
* - Outside the local_costmap (collision avoidance cannot be assured)
5959
* @param pose pose to transform
6060
* @param max_robot_pose_search_dist Distance to search for matching nearest path point
61+
* @param reject_unit_path If true, fail if path has only one pose
6162
* @return Path in new frame
6263
*/
6364
nav_msgs::msg::Path transformGlobalPlan(
6465
const geometry_msgs::msg::PoseStamped & pose,
65-
double max_robot_pose_search_dist);
66+
double max_robot_pose_search_dist, bool reject_unit_path = false);
6667

6768
/**
6869
* @brief Transform a pose to another frame.

nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,10 +131,12 @@ class RegulatedPurePursuitController : public nav2_core::Controller
131131
* @brief Whether robot should rotate to rough path heading
132132
* @param carrot_pose current lookahead point
133133
* @param angle_to_path Angle of robot output relatie to carrot marker
134+
* @param x_vel_sign Velocoty sign (forward or backward)
134135
* @return Whether should rotate to path heading
135136
*/
136137
bool shouldRotateToPath(
137-
const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path);
138+
const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
139+
double & x_vel_sign);
138140

139141
/**
140142
* @brief Whether robot should rotate to final goal orientation
@@ -185,9 +187,13 @@ class RegulatedPurePursuitController : public nav2_core::Controller
185187
* @brief Get lookahead point
186188
* @param lookahead_dist Optimal lookahead distance
187189
* @param path Current global path
190+
* @param interpolate_after_goal If true, interpolate the lookahead point after the goal based
191+
* on the orientation given by the position of the last two pose of the path
188192
* @return Lookahead point
189193
*/
190-
geometry_msgs::msg::PoseStamped getLookAheadPoint(const double &, const nav_msgs::msg::Path &);
194+
geometry_msgs::msg::PoseStamped getLookAheadPoint(
195+
const double &, const nav_msgs::msg::Path &,
196+
bool interpolate_after_goal = false);
191197

192198
/**
193199
* @brief checks for the cusp position
@@ -210,6 +216,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller
210216
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_path_pub_;
211217
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
212218
carrot_pub_;
219+
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PointStamped>>
220+
curvature_carrot_pub_;
213221
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> carrot_arc_pub_;
214222
std::unique_ptr<nav2_regulated_pure_pursuit_controller::PathHandler> path_handler_;
215223
std::unique_ptr<nav2_regulated_pure_pursuit_controller::ParameterHandler> param_handler_;

nav2_regulated_pure_pursuit_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010

1111
<buildtool_depend>ament_cmake</buildtool_depend>
1212

13+
<depend>nav2_amcl</depend>
1314
<depend>nav2_common</depend>
1415
<depend>nav2_core</depend>
1516
<depend>nav2_util</depend>

nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp

Lines changed: 12 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,9 @@ ParameterHandler::ParameterHandler(
9090
declare_parameter_if_not_declared(
9191
node, plugin_name_ + ".max_robot_pose_search_dist",
9292
rclcpp::ParameterValue(costmap_size_x / 2.0));
93+
declare_parameter_if_not_declared(
94+
node, plugin_name_ + ".interpolate_curvature_after_goal",
95+
rclcpp::ParameterValue(false));
9396
declare_parameter_if_not_declared(
9497
node, plugin_name_ + ".use_collision_detection",
9598
rclcpp::ParameterValue(true));
@@ -159,6 +162,15 @@ ParameterHandler::ParameterHandler(
159162
params_.max_robot_pose_search_dist = std::numeric_limits<double>::max();
160163
}
161164

165+
node->get_parameter(
166+
plugin_name_ + ".interpolate_curvature_after_goal",
167+
params_.interpolate_curvature_after_goal);
168+
if (!params_.use_fixed_curvature_lookahead && params_.interpolate_curvature_after_goal) {
169+
RCLCPP_WARN(
170+
logger_, "For interpolate_curvature_after_goal to be set to true, "
171+
"use_fixed_curvature_lookahead should be true, it is currently set to false. Disabling.");
172+
params_.interpolate_curvature_after_goal = false;
173+
}
162174
node->get_parameter(
163175
plugin_name_ + ".use_collision_detection",
164176
params_.use_collision_detection);
@@ -170,16 +182,6 @@ ParameterHandler::ParameterHandler(
170182
params_.use_cost_regulated_linear_velocity_scaling = false;
171183
}
172184

173-
/** Possible to drive in reverse direction if and only if
174-
"use_rotate_to_heading" parameter is set to false **/
175-
176-
if (params_.use_rotate_to_heading && params_.allow_reversing) {
177-
RCLCPP_WARN(
178-
logger_, "Disabling reversing. Both use_rotate_to_heading and allow_reversing "
179-
"parameter cannot be set to true. By default setting use_rotate_to_heading true");
180-
params_.allow_reversing = false;
181-
}
182-
183185
dyn_params_handler_ = node->add_on_set_parameters_callback(
184186
std::bind(
185187
&ParameterHandler::dynamicParametersCallback,
@@ -250,12 +252,6 @@ ParameterHandler::dynamicParametersCallback(
250252
} else if (name == plugin_name_ + ".use_collision_detection") {
251253
params_.use_collision_detection = parameter.as_bool();
252254
} else if (name == plugin_name_ + ".use_rotate_to_heading") {
253-
if (parameter.as_bool() && params_.allow_reversing) {
254-
RCLCPP_WARN(
255-
logger_, "Both use_rotate_to_heading and allow_reversing "
256-
"parameter cannot be set to true. Rejecting parameter update.");
257-
continue;
258-
}
259255
params_.use_rotate_to_heading = parameter.as_bool();
260256
} else if (name == plugin_name_ + ".allow_reversing") {
261257
if (params_.use_rotate_to_heading && parameter.as_bool()) {

nav2_regulated_pure_pursuit_controller/src/path_handler.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,12 +47,17 @@ double PathHandler::getCostmapMaxExtent() const
4747

4848
nav_msgs::msg::Path PathHandler::transformGlobalPlan(
4949
const geometry_msgs::msg::PoseStamped & pose,
50-
double max_robot_pose_search_dist)
50+
double max_robot_pose_search_dist,
51+
bool reject_unit_path)
5152
{
5253
if (global_plan_.poses.empty()) {
5354
throw nav2_core::InvalidPath("Received plan with zero length");
5455
}
5556

57+
if (reject_unit_path && global_plan_.poses.size() == 1) {
58+
throw nav2_core::InvalidPath("Received plan with length of one");
59+
}
60+
5661
// let's get the pose of the robot in the frame of the plan
5762
geometry_msgs::msg::PoseStamped robot_pose;
5863
if (!transformPose(global_plan_.header.frame_id, pose, robot_pose)) {
@@ -73,6 +78,15 @@ nav_msgs::msg::Path PathHandler::transformGlobalPlan(
7378
return euclidean_distance(robot_pose, ps);
7479
});
7580

81+
// Make sure we always have at least 2 points on the transformed plan and that we don't prune
82+
// the global plan below 2 points in order to have always enough point to interpolate the
83+
// end of path direction
84+
if (global_plan_.poses.begin() != closest_pose_upper_bound && global_plan_.poses.size() > 1 &&
85+
transformation_begin == std::prev(closest_pose_upper_bound))
86+
{
87+
transformation_begin = std::prev(std::prev(closest_pose_upper_bound));
88+
}
89+
7690
// We'll discard points on the plan that are outside the local costmap
7791
const double max_costmap_extent = getCostmapMaxExtent();
7892
auto transformation_end = std::find_if(

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

Lines changed: 54 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <vector>
2121
#include <utility>
2222

23+
#include "nav2_amcl/angleutils.hpp"
2324
#include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp"
2425
#include "nav2_core/controller_exceptions.hpp"
2526
#include "nav2_util/node_utils.hpp"
@@ -73,6 +74,8 @@ void RegulatedPurePursuitController::configure(
7374

7475
global_path_pub_ = node->create_publisher<nav_msgs::msg::Path>("received_global_plan", 1);
7576
carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>("lookahead_point", 1);
77+
curvature_carrot_pub_ = node->create_publisher<geometry_msgs::msg::PointStamped>(
78+
"curvature_lookahead_point", 1);
7679
}
7780

7881
void RegulatedPurePursuitController::cleanup()
@@ -84,6 +87,7 @@ void RegulatedPurePursuitController::cleanup()
8487
plugin_name_.c_str());
8588
global_path_pub_.reset();
8689
carrot_pub_.reset();
90+
curvature_carrot_pub_.reset();
8791
}
8892

8993
void RegulatedPurePursuitController::activate()
@@ -95,6 +99,7 @@ void RegulatedPurePursuitController::activate()
9599
plugin_name_.c_str());
96100
global_path_pub_->on_activate();
97101
carrot_pub_->on_activate();
102+
curvature_carrot_pub_->on_activate();
98103
}
99104

100105
void RegulatedPurePursuitController::deactivate()
@@ -106,6 +111,7 @@ void RegulatedPurePursuitController::deactivate()
106111
plugin_name_.c_str());
107112
global_path_pub_->on_deactivate();
108113
carrot_pub_->on_deactivate();
114+
curvature_carrot_pub_->on_deactivate();
109115
}
110116

111117
std::unique_ptr<geometry_msgs::msg::PointStamped> RegulatedPurePursuitController::createCarrotMsg(
@@ -171,7 +177,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
171177

172178
// Transform path to robot base frame
173179
auto transformed_plan = path_handler_->transformGlobalPlan(
174-
pose, params_->max_robot_pose_search_dist);
180+
pose, params_->max_robot_pose_search_dist, params_->interpolate_curvature_after_goal);
175181
global_path_pub_->publish(transformed_plan);
176182

177183
// Find look ahead distance and point on path and publish
@@ -190,6 +196,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
190196

191197
// Get the particular point on the path at the lookahead distance
192198
auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan);
199+
auto rotate_to_path_carrot_pose = carrot_pose;
193200
carrot_pub_->publish(createCarrotMsg(carrot_pose));
194201

195202
double linear_vel, angular_vel;
@@ -200,33 +207,39 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
200207
if (params_->use_fixed_curvature_lookahead) {
201208
auto curvature_lookahead_pose = getLookAheadPoint(
202209
params_->curvature_lookahead_dist,
203-
transformed_plan);
210+
transformed_plan, params_->interpolate_curvature_after_goal);
211+
rotate_to_path_carrot_pose = curvature_lookahead_pose;
204212
regulation_curvature = calculateCurvature(curvature_lookahead_pose.pose.position);
213+
curvature_carrot_pub_->publish(createCarrotMsg(curvature_lookahead_pose));
205214
}
206215

207216
// Setting the velocity direction
208-
double sign = 1.0;
217+
double x_vel_sign = 1.0;
209218
if (params_->allow_reversing) {
210-
sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
219+
x_vel_sign = carrot_pose.pose.position.x >= 0.0 ? 1.0 : -1.0;
211220
}
212221

213222
linear_vel = params_->desired_linear_vel;
214223

215224
// Make sure we're in compliance with basic constraints
225+
// For shouldRotateToPath, using x_vel_sign in order to support allow_reversing
226+
// and rotate_to_path_carrot_pose for the direction carrot pose:
227+
// - equal to "normal" carrot_pose when curvature_lookahead_pose = false
228+
// - otherwise equal to curvature_lookahead_pose (which can be interpolated after goal)
216229
double angle_to_heading;
217230
if (shouldRotateToGoalHeading(carrot_pose)) {
218231
double angle_to_goal = tf2::getYaw(transformed_plan.poses.back().pose.orientation);
219232
rotateToHeading(linear_vel, angular_vel, angle_to_goal, speed);
220-
} else if (shouldRotateToPath(carrot_pose, angle_to_heading)) {
233+
} else if (shouldRotateToPath(rotate_to_path_carrot_pose, angle_to_heading, x_vel_sign)) {
221234
rotateToHeading(linear_vel, angular_vel, angle_to_heading, speed);
222235
} else {
223236
applyConstraints(
224237
regulation_curvature, speed,
225238
collision_checker_->costAtPose(pose.pose.position.x, pose.pose.position.y), transformed_plan,
226-
linear_vel, sign);
239+
linear_vel, x_vel_sign);
227240

228241
// Apply curvature to angular velocity after constraining linear velocity
229-
angular_vel = linear_vel * lookahead_curvature;
242+
angular_vel = linear_vel * regulation_curvature;
230243
}
231244

232245
// Collision checking on this velocity heading
@@ -246,10 +259,15 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
246259
}
247260

248261
bool RegulatedPurePursuitController::shouldRotateToPath(
249-
const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path)
262+
const geometry_msgs::msg::PoseStamped & carrot_pose, double & angle_to_path,
263+
double & x_vel_sign)
250264
{
251265
// Whether we should rotate robot to rough path heading
252266
angle_to_path = atan2(carrot_pose.pose.position.y, carrot_pose.pose.position.x);
267+
// In case we are reversing
268+
if (x_vel_sign < 0.0) {
269+
angle_to_path = nav2_amcl::angleutils::normalize(angle_to_path + M_PI);
270+
}
253271
return params_->use_rotate_to_heading &&
254272
fabs(angle_to_path) > params_->rotate_to_heading_min_angle;
255273
}
@@ -314,7 +332,8 @@ geometry_msgs::msg::Point RegulatedPurePursuitController::circleSegmentIntersect
314332

315333
geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoint(
316334
const double & lookahead_dist,
317-
const nav_msgs::msg::Path & transformed_plan)
335+
const nav_msgs::msg::Path & transformed_plan,
336+
bool interpolate_after_goal)
318337
{
319338
// Find the first pose which is at a distance greater than the lookahead distance
320339
auto goal_pose_it = std::find_if(
@@ -324,7 +343,32 @@ geometry_msgs::msg::PoseStamped RegulatedPurePursuitController::getLookAheadPoin
324343

325344
// If the no pose is not far enough, take the last pose
326345
if (goal_pose_it == transformed_plan.poses.end()) {
327-
goal_pose_it = std::prev(transformed_plan.poses.end());
346+
if (interpolate_after_goal) {
347+
auto last_pose_it = std::prev(transformed_plan.poses.end());
348+
auto prev_last_pose_it = std::prev(last_pose_it);
349+
350+
double end_path_orientation = atan2(
351+
last_pose_it->pose.position.y - prev_last_pose_it->pose.position.y,
352+
last_pose_it->pose.position.x - prev_last_pose_it->pose.position.x);
353+
354+
// Project the last segment out to guarantee it is beyond the look ahead
355+
// distance
356+
auto projected_position = last_pose_it->pose.position;
357+
projected_position.x += cos(end_path_orientation) * lookahead_dist;
358+
projected_position.y += sin(end_path_orientation) * lookahead_dist;
359+
360+
// Use the circle intersection to find the position at the correct look
361+
// ahead distance
362+
const auto interpolated_position = circleSegmentIntersection(
363+
last_pose_it->pose.position, projected_position, lookahead_dist);
364+
365+
geometry_msgs::msg::PoseStamped interpolated_pose;
366+
interpolated_pose.header = last_pose_it->header;
367+
interpolated_pose.pose.position = interpolated_position;
368+
return interpolated_pose;
369+
} else {
370+
goal_pose_it = std::prev(transformed_plan.poses.end());
371+
}
328372
} else if (goal_pose_it != transformed_plan.poses.begin()) {
329373
// Find the point on the line segment between the two poses
330374
// that is exactly the lookahead distance away from the robot pose (the origin)

0 commit comments

Comments
 (0)