Skip to content

Commit

Permalink
added suggestion
Browse files Browse the repository at this point in the history
  • Loading branch information
chfriedrich98 committed Jul 17, 2024
1 parent 31f08d8 commit 83bcedf
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/lib/pure_pursuit/PurePursuit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,9 @@ float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2
}

const Vector2f prev_wp_to_curr_pos = curr_pos_ned - prev_wp_ned;
const Vector2f distance_on_line_segment = ((prev_wp_to_curr_pos * prev_wp_to_curr_wp) /
prev_wp_to_curr_wp.norm()) *
prev_wp_to_curr_wp.normalized(); // Projection of prev_wp_to_curr_pos onto prev_wp_to_curr_wp
const Vector2f prev_wp_to_curr_wp_u = prev_wp_to_curr_wp.unit_or_zero();
const Vector2f distance_on_line_segment = (prev_wp_to_curr_pos * prev_wp_to_curr_wp_u) *
prev_wp_to_curr_wp_u; // Projection of prev_wp_to_curr_pos onto prev_wp_to_curr_wp
const Vector2f curr_pos_to_path = distance_on_line_segment -
prev_wp_to_curr_pos; // Shortest vector from the current position to the path

Expand All @@ -68,7 +68,7 @@ float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2
const float line_extension = sqrt(powf(lookahead_distance, 2.f) - powf(curr_pos_to_path.norm(),
2.f)); // Length of the vector from the endpoint of distance_on_line_segment to the intersection point
const Vector2f prev_wp_to_intersection_point = distance_on_line_segment + line_extension *
distance_on_line_segment.normalized();
prev_wp_to_curr_wp_u;
const Vector2f curr_pos_to_intersection_point = prev_wp_to_intersection_point - prev_wp_to_curr_pos;
return atan2f(curr_pos_to_intersection_point(1), curr_pos_to_intersection_point(0));

Expand Down

0 comments on commit 83bcedf

Please sign in to comment.