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

Base (abstract) class for longitudinal controllers (the ones that calculate throttle) More...

#include <base_longitudinal_controller.hpp>

Inheritance diagram for LongitudinalController:
Inheritance graph
Collaboration diagram for LongitudinalController:
Collaboration graph

Public Member Functions

virtual void path_callback (const custom_interfaces::msg::PathPointArray &msg)=0
 Called when a new path is sent by Path Planning.
 
virtual void vehicle_state_callback (const custom_interfaces::msg::Velocities &msg)=0
 Called when the car state (currently just velocity) is updated.
 
virtual void vehicle_pose_callback (const custom_interfaces::msg::Pose &msg)=0
 Called when the car pose is updated by SLAM.
 
virtual common_lib::structures::ControlCommand get_throttle_command ()=0
 Returns the throttle command calculated by the solver (only throttle)
 
virtual void publish_solver_data (std::shared_ptr< rclcpp::Node > node, std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &publisher_map)=0
 Publishes solver specific data using the provided ControlNode.
 
 LongitudinalController (const ControlParameters &params)
 
virtual ~LongitudinalController ()=default
 

Protected Attributes

std::shared_ptr< ControlParametersparams_
 

Detailed Description

Base (abstract) class for longitudinal controllers (the ones that calculate throttle)

Definition at line 13 of file base_longitudinal_controller.hpp.

Constructor & Destructor Documentation

◆ LongitudinalController()

LongitudinalController::LongitudinalController ( const ControlParameters params)
inline

Definition at line 45 of file base_longitudinal_controller.hpp.

◆ ~LongitudinalController()

virtual LongitudinalController::~LongitudinalController ( )
virtualdefault

Member Function Documentation

◆ get_throttle_command()

virtual common_lib::structures::ControlCommand LongitudinalController::get_throttle_command ( )
pure virtual

Returns the throttle command calculated by the solver (only throttle)

Implemented in PID.

◆ path_callback()

virtual void LongitudinalController::path_callback ( const custom_interfaces::msg::PathPointArray &  msg)
pure virtual

Called when a new path is sent by Path Planning.

Implemented in PID.

◆ publish_solver_data()

virtual void LongitudinalController::publish_solver_data ( std::shared_ptr< rclcpp::Node >  node,
std::map< std::string, std::shared_ptr< rclcpp::PublisherBase > > &  publisher_map 
)
pure virtual

Publishes solver specific data using the provided ControlNode.

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

Implemented in PID.

◆ vehicle_pose_callback()

virtual void LongitudinalController::vehicle_pose_callback ( const custom_interfaces::msg::Pose &  msg)
pure virtual

Called when the car pose is updated by SLAM.

Implemented in PID.

◆ vehicle_state_callback()

virtual void LongitudinalController::vehicle_state_callback ( const custom_interfaces::msg::Velocities &  msg)
pure virtual

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

Implemented in PID.

Member Data Documentation

◆ params_

std::shared_ptr<ControlParameters> LongitudinalController::params_
protected

Definition at line 15 of file base_longitudinal_controller.hpp.


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