Skip to content
Merged
Changes from all commits
Commits
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
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,7 @@

// Find look ahead distance and point on path and publish
double lookahead_dist = getLookAheadDistance(speed);
double curv_lookahead_dist = params_->curvature_lookahead_dist;

// Check for reverse driving
if (params_->allow_reversing) {
Expand All @@ -197,6 +198,9 @@
if (dist_to_cusp < lookahead_dist) {
lookahead_dist = dist_to_cusp;
}
if (dist_to_cusp < curv_lookahead_dist) {
curv_lookahead_dist = dist_to_cusp;

Check warning on line 202 in nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp#L201-L202

Added lines #L201 - L202 were not covered by tests
}
}

// Get the particular point on the path at the lookahead distance
Expand All @@ -211,7 +215,7 @@
double regulation_curvature = lookahead_curvature;
if (params_->use_fixed_curvature_lookahead) {
auto curvature_lookahead_pose = getLookAheadPoint(
params_->curvature_lookahead_dist,
curv_lookahead_dist,
transformed_plan, params_->interpolate_curvature_after_goal);
rotate_to_path_carrot_pose = curvature_lookahead_pose;
regulation_curvature = calculateCurvature(curvature_lookahead_pose.pose.position);
Expand Down
Loading