Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
PurePursuit Class Reference

Pure Pursuit class. More...

#include <pure_pursuit.hpp>

Inheritance diagram for PurePursuit:
Inheritance graph
Collaboration diagram for PurePursuit:
Collaboration graph

Public Member Functions

 PurePursuit (const ControlParameters &params)
 Construct a new Pure Pursuit object.
 
void path_callback (const custom_interfaces::msg::PathPointArray &msg) override
 Called when a new path is sent by Path Planning.
 
void vehicle_state_callback (const custom_interfaces::msg::Velocities &msg) override
 Called when the car state (currently just velocity) is updated.
 
void vehicle_pose_callback (const custom_interfaces::msg::Pose &msg) override
 Called when the car pose is updated by SLAM.
 
double get_steering_command () override
 Returns the steering command calculated by the solver.
 
void publish_solver_data (std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map) override
 Publishes solver specific data using the provided ControlNode.
 
double pp_steering_control_law (common_lib::structures::Position rear_axis, common_lib::structures::Position cg, common_lib::structures::Position lookahead_point, double dist_cg_2_rear_axis)
 Pure Pursuit control law.
 
double calculate_alpha (common_lib::structures::Position vehicle_rear_wheel, common_lib::structures::Position vehicle_cg, common_lib::structures::Position lookahead_point, double rear_wheel_2_c_g)
 Calculate alpha (angle between the vehicle and lookahead point)
 
 FRIEND_TEST (PurePursuitTests, Test_calculate_alpha_1)
 
 FRIEND_TEST (PurePursuitTests, Test_calculate_alpha_2)
 
 FRIEND_TEST (PurePursuitTests, Test_calculate_alpha_3)
 
 FRIEND_TEST (PurePursuitTests, Test_calculate_alpha_4)
 
 FRIEND_TEST (PurePursuitTests, Test_calculate_alpha_5)
 
 FRIEND_TEST (PurePursuitTests, Test_pp_steering_control_law_1)
 
- Public Member Functions inherited from LateralController
 LateralController (const ControlParameters &params)
 
virtual ~LateralController ()=default
 

Private Member Functions

void publish_closest_point (std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map)
 Function that publishes the closest point marker.
 
void publish_lookahead_point (std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map)
 Function that publishes the lookahead point marker.
 

Private Attributes

std::shared_ptr< Filterlpf_
 
std::vector< custom_interfaces::msg::PathPoint > last_path_msg_
 
custom_interfaces::msg::Velocities last_velocity_msg_
 
custom_interfaces::msg::Pose last_pose_msg_
 
double absolute_velocity_ = 0.0
 
bool received_first_path_ = false
 
bool received_first_state_ = false
 
bool received_first_pose_ = false
 
common_lib::structures::Position closest_point_
 
common_lib::structures::Position lookahead_point_
 

Additional Inherited Members

- Protected Attributes inherited from LateralController
std::shared_ptr< ControlParametersparams_
 

Detailed Description

Pure Pursuit class.

This class implements a Pure Pursuit controller. This assumes a bicycle model for the vehicle. The two main functions are:

  • Calculate the lookahead point
  • Calculate the steering angle (Pure Pursuit Control Law)

Definition at line 26 of file pure_pursuit.hpp.

Constructor & Destructor Documentation

◆ PurePursuit()

PurePursuit::PurePursuit ( const ControlParameters params)

Construct a new Pure Pursuit object.

Pure Pursuit class Constructor.

Parameters
paramsControl parameters

Definition at line 9 of file pure_pursuit.cpp.

Member Function Documentation

◆ calculate_alpha()

double PurePursuit::calculate_alpha ( common_lib::structures::Position  vehicle_rear_wheel,
common_lib::structures::Position  vehicle_cg,
common_lib::structures::Position  lookahead_point,
double  rear_wheel_2_c_g 
)

Calculate alpha (angle between the vehicle and lookahead point)

Parameters
vehicle_rear_wheel
vehicle_cg
lookahead_point
dist_cg_2_rear_axis
Returns
double

Definition at line 72 of file pure_pursuit.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ FRIEND_TEST() [1/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_calculate_alpha_1   
)

◆ FRIEND_TEST() [2/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_calculate_alpha_2   
)

◆ FRIEND_TEST() [3/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_calculate_alpha_3   
)

◆ FRIEND_TEST() [4/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_calculate_alpha_4   
)

◆ FRIEND_TEST() [5/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_calculate_alpha_5   
)

◆ FRIEND_TEST() [6/6]

PurePursuit::FRIEND_TEST ( PurePursuitTests  ,
Test_pp_steering_control_law_1   
)

◆ get_steering_command()

double PurePursuit::get_steering_command ( )
overridevirtual

Returns the steering command calculated by the solver.

Implements LateralController.

Definition at line 28 of file pure_pursuit.cpp.

Here is the call graph for this function:

◆ path_callback()

void PurePursuit::path_callback ( const custom_interfaces::msg::PathPointArray &  msg)
overridevirtual

Called when a new path is sent by Path Planning.

Implements LateralController.

Definition at line 12 of file pure_pursuit.cpp.

◆ pp_steering_control_law()

double PurePursuit::pp_steering_control_law ( common_lib::structures::Position  rear_axis,
common_lib::structures::Position  cg,
common_lib::structures::Position  lookahead_point,
double  dist_cg_2_rear_axis 
)

Pure Pursuit control law.

Parameters
rear_axis
cgcenter of gravity
lookahead_point
dist_cg_2_rear_axisdistance between center of gravity and rear axis
Returns
Steering angle

Definition at line 59 of file pure_pursuit.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_closest_point()

void PurePursuit::publish_closest_point ( std::shared_ptr< rclcpp::Node >  node,
std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &  publisher_map 
)
private

Function that publishes the closest point marker.

Parameters
nodepointer to the rclcpp node
publisher_mapmap between topic names and publishers

Definition at line 97 of file pure_pursuit.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_lookahead_point()

void PurePursuit::publish_lookahead_point ( std::shared_ptr< rclcpp::Node >  node,
std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &  publisher_map 
)
private

Function that publishes the lookahead point marker.

Parameters
nodepointer to the rclcpp node
publisher_mapmap between topic names and publishers

Definition at line 109 of file pure_pursuit.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_solver_data()

void PurePursuit::publish_solver_data ( std::shared_ptr< rclcpp::Node >  node,
std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &  publisher_map 
)
overridevirtual

Publishes solver specific data using the provided ControlNode.

Parameters
nodeshared pointer to the ControlNode
publisher_mapmap of topic names to publisher pointers

Implements LateralController.

Definition at line 92 of file pure_pursuit.cpp.

Here is the call graph for this function:

◆ vehicle_pose_callback()

void PurePursuit::vehicle_pose_callback ( const custom_interfaces::msg::Pose &  msg)
overridevirtual

Called when the car pose is updated by SLAM.

Implements LateralController.

Definition at line 23 of file pure_pursuit.cpp.

◆ vehicle_state_callback()

void PurePursuit::vehicle_state_callback ( const custom_interfaces::msg::Velocities &  msg)
overridevirtual

Called when the car state (currently just velocity) is updated.

Implements LateralController.

Definition at line 17 of file pure_pursuit.cpp.

Member Data Documentation

◆ absolute_velocity_

double PurePursuit::absolute_velocity_ = 0.0
private

Definition at line 35 of file pure_pursuit.hpp.

◆ closest_point_

common_lib::structures::Position PurePursuit::closest_point_
private

Definition at line 43 of file pure_pursuit.hpp.

◆ last_path_msg_

std::vector<custom_interfaces::msg::PathPoint> PurePursuit::last_path_msg_
private

Definition at line 32 of file pure_pursuit.hpp.

◆ last_pose_msg_

custom_interfaces::msg::Pose PurePursuit::last_pose_msg_
private

Definition at line 34 of file pure_pursuit.hpp.

◆ last_velocity_msg_

custom_interfaces::msg::Velocities PurePursuit::last_velocity_msg_
private

Definition at line 33 of file pure_pursuit.hpp.

◆ lookahead_point_

common_lib::structures::Position PurePursuit::lookahead_point_
private

Definition at line 44 of file pure_pursuit.hpp.

◆ lpf_

std::shared_ptr<Filter> PurePursuit::lpf_
private

Definition at line 29 of file pure_pursuit.hpp.

◆ received_first_path_

bool PurePursuit::received_first_path_ = false
private

Definition at line 38 of file pure_pursuit.hpp.

◆ received_first_pose_

bool PurePursuit::received_first_pose_ = false
private

Definition at line 40 of file pure_pursuit.hpp.

◆ received_first_state_

bool PurePursuit::received_first_state_ = false
private

Definition at line 39 of file pure_pursuit.hpp.


The documentation for this class was generated from the following files: