Autoware.Auto
autoware::motion::control::trajectory_follower::PIDController Class Reference

implementation of a PID controller More...

#include <pid.hpp>

Public Member Functions

 PIDController ()
 
float64_t calculate (const float64_t error, const float64_t dt, const bool8_t is_integrated, std::vector< float64_t > &pid_contributions)
 calculate the output of this PID More...
 
void setGains (const float64_t kp, const float64_t ki, const float64_t kd)
 set the coefficients for the P (proportional) I (integral) D (derivative) terms More...
 
void setLimits (const float64_t max_ret, const float64_t min_ret, const float64_t max_ret_p, const float64_t min_ret_p, const float64_t max_ret_i, const float64_t min_ret_i, const float64_t max_ret_d, const float64_t min_ret_d)
 set limits on the total, proportional, integral, and derivative components More...
 
void reset ()
 reset this PID to its initial state More...
 

Detailed Description

implementation of a PID controller

Constructor & Destructor Documentation

◆ PIDController()

autoware::motion::control::trajectory_follower::PIDController::PIDController ( )

Member Function Documentation

◆ calculate()

float64_t autoware::motion::control::trajectory_follower::PIDController::calculate ( const float64_t  error,
const float64_t  dt,
const bool8_t  is_integrated,
std::vector< float64_t > &  pid_contributions 
)

calculate the output of this PID

Parameters
[in]errorprevious error
[in]dttime step [s]
[in]is_integratedif true, will use the integral component for calculation
[out]pid_contributionsvalues of the proportional, integral, and derivative components
Returns
PID output
Exceptions
std::runtime_errorif gains or limits have not been set

◆ reset()

void autoware::motion::control::trajectory_follower::PIDController::reset ( )

reset this PID to its initial state

◆ setGains()

void autoware::motion::control::trajectory_follower::PIDController::setGains ( const float64_t  kp,
const float64_t  ki,
const float64_t  kd 
)

set the coefficients for the P (proportional) I (integral) D (derivative) terms

Parameters
[in]kpproportional coefficient
[in]kiintegral coefficient
[in]kdderivative coefficient

◆ setLimits()

void autoware::motion::control::trajectory_follower::PIDController::setLimits ( const float64_t  max_ret,
const float64_t  min_ret,
const float64_t  max_ret_p,
const float64_t  min_ret_p,
const float64_t  max_ret_i,
const float64_t  min_ret_i,
const float64_t  max_ret_d,
const float64_t  min_ret_d 
)

set limits on the total, proportional, integral, and derivative components

Parameters
[in]max_retmaximum return value of this PID
[in]min_retminimum return value of this PID
[in]max_ret_pmaximum value of the proportional component
[in]min_ret_pminimum value of the proportional component
[in]max_ret_imaximum value of the integral component
[in]min_ret_iminimum value of the integral component
[in]max_ret_dmaximum value of the derivative component
[in]min_ret_dminimum value of the derivative component

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