Skip to content

Commit

Permalink
fixed pr check fails
Browse files Browse the repository at this point in the history
  • Loading branch information
chfriedrich98 committed Apr 18, 2024
1 parent 1b81db8 commit 6fd8baf
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
1 change: 0 additions & 1 deletion ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@

#!/bin/sh
# Ackermann rover parameters.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,9 +194,9 @@ void AckermannDriveGuidance::purePursuit()
_ackermann_drive_setpoint_pub.publish(_ackermann_drive_setpoint);
}

float AckermannDriveGuidance::calcDesiredHeading(Vector2f curr_wp_local, Vector2f prev_wp_local,
Vector2f curr_pos_local,
float lookahead_distance)
float AckermannDriveGuidance::calcDesiredHeading(Vector2f const &curr_wp_local, Vector2f const &prev_wp_local,
Vector2f const &curr_pos_local,
float const &lookahead_distance)
{
// Setup variables
float line_segment_slope = (curr_wp_local(1) - prev_wp_local(1)) / (curr_wp_local(0) - prev_wp_local(0));
Expand Down Expand Up @@ -239,8 +239,8 @@ float AckermannDriveGuidance::calcDesiredHeading(Vector2f curr_wp_local, Vector2
}
}

void AckermannDriveGuidance::updateAcceptanceRadius(Vector2f curr_wp_local, Vector2f prev_wp_local,
Vector2f next_wp_local)
void AckermannDriveGuidance::updateAcceptanceRadius(Vector2f const &curr_wp_local, Vector2f const &prev_wp_local,
Vector2f const &next_wp_local)
{
// Setup variables
Vector2f curr_to_prev_wp_local = prev_wp_local - curr_wp_local;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,8 @@ class AckermannDriveGuidance : public ModuleParams
* @param curr_pos_local Current position of the vehicle in local frame.
* @param lookahead_distance Radius of circle around vehicle.
*/
float calcDesiredHeading(Vector2f curr_wp_local, Vector2f prev_wp_local, Vector2f curr_pos_local,
float lookahead_distance);
float calcDesiredHeading(Vector2f const &curr_wp_local, Vector2f const &prev_wp_local, Vector2f const &curr_pos_local,
float const &lookahead_distance);

/**
* @brief Publishes the acceptance radius for current waypoint based on the angle between a line segment
Expand All @@ -102,7 +102,8 @@ class AckermannDriveGuidance : public ModuleParams
* @param prev_wp_local Previous waypoint in local frame.
* @param next_wp_local Next waypoint in local frame.
*/
void updateAcceptanceRadius(Vector2f curr_wp_local, Vector2f prev_wp_local, Vector2f next_wp_local);
void updateAcceptanceRadius(Vector2f const &curr_wp_local, Vector2f const &prev_wp_local,
Vector2f const &next_wp_local);

protected:
/**
Expand Down

0 comments on commit 6fd8baf

Please sign in to comment.