Skip to content

Commit

Permalink
add citation and remove pass by reference for native type
Browse files Browse the repository at this point in the history
  • Loading branch information
chfriedrich98 committed Jul 18, 2024
1 parent 83bcedf commit ec4923f
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 2 deletions.
2 changes: 1 addition & 1 deletion src/lib/pure_pursuit/PurePursuit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned,
const Vector2f &curr_pos_ned,
const float &lookahead_distance)
const float lookahead_distance)
{
// Check input validity
if (!curr_wp_ned.isAllFinite() || !curr_pos_ned.isAllFinite() || lookahead_distance < FLT_EPSILON
Expand Down
9 changes: 8 additions & 1 deletion src/lib/pure_pursuit/PurePursuit.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,13 @@ using namespace matrix;
*
* Implementation of pure pursuit guidance logic.
*
* Acknowledgements and References:
*
* This implementation has been built for PX4 based on the idea from [1] (not including any code).
*
* [1] Coulter, R. C. (1992). Implementation of the Pure Pursuit Path Tracking Algorithm
* (Techreport CMU-RI-TR-92-01).
*
* Pure pursuit is a path following algorithm that uses the intersection between the path and
* a circle (the radius of which is referred to as lookahead distance) around the vehicle as
* the target point for the vehicle.
Expand Down Expand Up @@ -80,5 +87,5 @@ class PurePursuit
* @param lookahead_distance Radius of circle around vehicle [m].
*/
float calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, const Vector2f &curr_pos_ned,
const float &lookahead_distance);
const float lookahead_distance);
};

0 comments on commit ec4923f

Please sign in to comment.