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

PI-D Controller class. More...

#include <pid.hpp>

Inheritance diagram for PID:
Inheritance graph
Collaboration diagram for PID:
Collaboration graph

Public Member Functions

 PID (const ControlParameters &params)
 Construct a new PID 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.
 
common_lib::structures::ControlCommand get_throttle_command () override
 Returns the throttle command calculated by the solver (only throttle)
 
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.
 
 FRIEND_TEST (PidTests, TestAntiWindUp1)
 
 FRIEND_TEST (PidTests, TestAntiWindUp2)
 
 FRIEND_TEST (PidTests, TestAntiWindUp3)
 
 FRIEND_TEST (PidTests, ProportionalTerm)
 
 FRIEND_TEST (PidTests, IntegralTerm1)
 
 FRIEND_TEST (PidTests, IntegralTerm2)
 
 FRIEND_TEST (PidTests, DerivativeTerm1)
 
 FRIEND_TEST (PidTests, DerivativeTerm2)
 
 FRIEND_TEST (PidTests, Output1)
 
 FRIEND_TEST (PidTests, Output2)
 
 FRIEND_TEST (PidTests, Output3)
 
 FRIEND_TEST (PidTests, Update1)
 
- Public Member Functions inherited from LongitudinalController
 LongitudinalController (const ControlParameters &params)
 
virtual ~LongitudinalController ()=default
 

Private Member Functions

double calculate_error (double setpoint, double measurement) const
 Calculate the error signal.
 
void calculate_proportional_term (double error)
 Calculate the proportional term.
 
void calculate_integral_term (double error)
 Calculate the integral term.
 
void anti_wind_up ()
 Anti-wind-up via dynamic integrator clamping.
 
void calculate_derivative_term (double measurement)
 Calculate the derivative term (derivative on measurement)
 
void compute_output ()
 Compute the output value and apply limits.
 
double update (double setpoint, double measurement)
 Calculate the output value.
 

Private Attributes

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
 
double proportional_ {0.0f}
 Proportional term current value.
 
double integrator_ {0.0f}
 Integrator term current value.
 
double differentiator_ {0.0f}
 Differentiator term current value.
 
double prev_error_ {0.0f}
 Previous error value, required for integrator.
 
double prev_measurement_ {0.0f}
 Previous measurement value, required for defferentiator.
 
double out_ {0.0f}
 Current output value.
 

Additional Inherited Members

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

Detailed Description

PI-D Controller class.

This class implements a PI-D controller. Its a PI-D because the P and I terms operates on the Error signal and the D works with the feedback signal (measurement).

Definition at line 18 of file pid.hpp.

Constructor & Destructor Documentation

◆ PID()

PID::PID ( const ControlParameters params)

Construct a new PID object.

Parameters
paramsControl parameters

Definition at line 9 of file pid.cpp.

Member Function Documentation

◆ anti_wind_up()

void PID::anti_wind_up ( )
private

Anti-wind-up via dynamic integrator clamping.

Definition at line 77 of file pid.cpp.

Here is the caller graph for this function:

◆ calculate_derivative_term()

void PID::calculate_derivative_term ( double  measurement)
private

Calculate the derivative term (derivative on measurement)

Parameters
measurement

Definition at line 84 of file pid.cpp.

Here is the caller graph for this function:

◆ calculate_error()

double PID::calculate_error ( double  setpoint,
double  measurement 
) const
private

Calculate the error signal.

Parameters
setpoint
measurement
Returns
error (double)

Definition at line 56 of file pid.cpp.

Here is the caller graph for this function:

◆ calculate_integral_term()

void PID::calculate_integral_term ( double  error)
private

Calculate the integral term.

Parameters
error

Definition at line 72 of file pid.cpp.

Here is the caller graph for this function:

◆ calculate_proportional_term()

void PID::calculate_proportional_term ( double  error)
private

Calculate the proportional term.

Parameters
error

Definition at line 68 of file pid.cpp.

Here is the caller graph for this function:

◆ compute_output()

void PID::compute_output ( )
private

Compute the output value and apply limits.

Definition at line 91 of file pid.cpp.

Here is the caller graph for this function:

◆ FRIEND_TEST() [1/12]

PID::FRIEND_TEST ( PidTests  ,
DerivativeTerm1   
)

◆ FRIEND_TEST() [2/12]

PID::FRIEND_TEST ( PidTests  ,
DerivativeTerm2   
)

◆ FRIEND_TEST() [3/12]

PID::FRIEND_TEST ( PidTests  ,
IntegralTerm1   
)

◆ FRIEND_TEST() [4/12]

PID::FRIEND_TEST ( PidTests  ,
IntegralTerm2   
)

◆ FRIEND_TEST() [5/12]

PID::FRIEND_TEST ( PidTests  ,
Output1   
)

◆ FRIEND_TEST() [6/12]

PID::FRIEND_TEST ( PidTests  ,
Output2   
)

◆ FRIEND_TEST() [7/12]

PID::FRIEND_TEST ( PidTests  ,
Output3   
)

◆ FRIEND_TEST() [8/12]

PID::FRIEND_TEST ( PidTests  ,
ProportionalTerm   
)

◆ FRIEND_TEST() [9/12]

PID::FRIEND_TEST ( PidTests  ,
TestAntiWindUp1   
)

◆ FRIEND_TEST() [10/12]

PID::FRIEND_TEST ( PidTests  ,
TestAntiWindUp2   
)

◆ FRIEND_TEST() [11/12]

PID::FRIEND_TEST ( PidTests  ,
TestAntiWindUp3   
)

◆ FRIEND_TEST() [12/12]

PID::FRIEND_TEST ( PidTests  ,
Update1   
)

◆ get_throttle_command()

common_lib::structures::ControlCommand PID::get_throttle_command ( )
overridevirtual

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

Implements LongitudinalController.

Definition at line 117 of file pid.cpp.

Here is the call graph for this function:

◆ path_callback()

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

Called when a new path is sent by Path Planning.

Implements LongitudinalController.

Definition at line 103 of file pid.cpp.

◆ publish_solver_data()

void PID::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 LongitudinalController.

Definition at line 136 of file pid.cpp.

◆ update()

double PID::update ( double  setpoint,
double  measurement 
)
private

Calculate the output value.

Parameters
setpointgoal value
measurementcurrent value
Returns
double
Parameters
setpoint
measurement
Returns
double

Definition at line 19 of file pid.cpp.

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

◆ vehicle_pose_callback()

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

Called when the car pose is updated by SLAM.

Implements LongitudinalController.

Definition at line 112 of file pid.cpp.

◆ vehicle_state_callback()

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

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

Implements LongitudinalController.

Definition at line 107 of file pid.cpp.

Member Data Documentation

◆ absolute_velocity_

double PID::absolute_velocity_ = 0.0
private

Definition at line 23 of file pid.hpp.

◆ differentiator_

double PID::differentiator_ {0.0f}
private

Differentiator term current value.

Definition at line 31 of file pid.hpp.

◆ integrator_

double PID::integrator_ {0.0f}
private

Integrator term current value.

Definition at line 30 of file pid.hpp.

◆ last_path_msg_

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

Definition at line 20 of file pid.hpp.

◆ last_pose_msg_

custom_interfaces::msg::Pose PID::last_pose_msg_
private

Definition at line 22 of file pid.hpp.

◆ last_velocity_msg_

custom_interfaces::msg::Velocities PID::last_velocity_msg_
private

Definition at line 21 of file pid.hpp.

◆ out_

double PID::out_ {0.0f}
private

Current output value.

Definition at line 36 of file pid.hpp.

◆ prev_error_

double PID::prev_error_ {0.0f}
private

Previous error value, required for integrator.

Definition at line 33 of file pid.hpp.

◆ prev_measurement_

double PID::prev_measurement_ {0.0f}
private

Previous measurement value, required for defferentiator.

Definition at line 34 of file pid.hpp.

◆ proportional_

double PID::proportional_ {0.0f}
private

Proportional term current value.

Definition at line 29 of file pid.hpp.

◆ received_first_path_

bool PID::received_first_path_ = false
private

Definition at line 25 of file pid.hpp.

◆ received_first_pose_

bool PID::received_first_pose_ = false
private

Definition at line 27 of file pid.hpp.

◆ received_first_state_

bool PID::received_first_state_ = false
private

Definition at line 26 of file pid.hpp.


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