chrono::vehicle::ChPathSteeringControllerXT Class Reference

Description

Concrete path-following steering 3(2) channel PDT1/PT1 controller.

The path to be followed is specified as a ChBezierCurve object and the target point is defined to be the point on that path that is closest to the current location of the sentinel point. The sentinel point should never leave the end or beginning of the path. The controller is sensitive to tire relaxiation, when steering oscillations occure and do not calm down after a short driving distance, Kp should be reduced carefully.

#include <ChSteeringController.h>

Inheritance diagram for chrono::vehicle::ChPathSteeringControllerXT:
Collaboration diagram for chrono::vehicle::ChPathSteeringControllerXT:

Public Member Functions

 ChPathSteeringControllerXT (std::shared_ptr< ChBezierCurve > path, bool isClosedPath=false, double max_wheel_turn_angle=0.0)
 Construct a steering controller to track the specified path. More...
 
 ChPathSteeringControllerXT (const std::string &filename, std::shared_ptr< ChBezierCurve > path, bool isClosedPath=false, double max_wheel_turn_angle=0.0)
 Construct a steering controller to track the specified path. More...
 
 ~ChPathSteeringControllerXT ()
 Destructor for ChPathSteeringController.
 
std::shared_ptr< ChBezierCurveGetPath () const
 Return a pointer to the Bezier curve.
 
virtual void Reset (const ChVehicle &vehicle) override
 Reset the PID controller. More...
 
void SetGains (double Kp=0.4, double W_y_err=1.0, double W_heading_err=1.0, double W_ackermann=1.0)
 Set the gains (weighting factors) for the eXTended controller.
 
virtual void CalcTargetLocation () override
 Calculate the current target point location. More...
 
double Advance (const ChVehicle &vehicle, double step)
 
- Public Member Functions inherited from chrono::vehicle::ChSteeringController
 ChSteeringController ()
 Construct a steering controller with default parameters. More...
 
 ChSteeringController (const std::string &filename)
 Construct a steering controller with parameters read from a JSON file.
 
virtual ~ChSteeringController ()
 Destructor.
 
void SetLookAheadDistance (double dist)
 Specify the look-ahead distance. More...
 
void SetGains (double Kp, double Ki, double Kd)
 Set the gains for the PID controller.
 
const ChVectorGetSentinelLocation () const
 Return the current location of the sentinel point. More...
 
const ChVectorGetTargetLocation () const
 Return the current value of the target point. More...
 
double Advance (const ChVehicle &vehicle, double step)
 Advance the state of the PID controller. More...
 
void StartDataCollection ()
 Start/restart data collection.
 
void StopDataCollection ()
 Suspend/stop data collection.
 
bool IsDataCollectionEnabled () const
 Return true if data is being collected.
 
bool IsDataAvailable () const
 Return true if data is available for output.
 
void WriteOutputFile (const std::string &filename)
 Output data collected so far to the specified file.
 

Additional Inherited Members

- Protected Attributes inherited from chrono::vehicle::ChSteeringController
double m_dist
 look-ahead distance
 
ChVector m_sentinel
 position of sentinel point in global frame
 
ChVector m_target
 position of target point in global frame
 
double m_Kp
 
double m_Ki
 PID controller gains.
 
double m_Kd
 
double m_err
 current error (signed distance to target point)
 
double m_errd
 error derivative
 
double m_erri
 integral of error
 
utils::CSV_writer * m_csv
 CSV_writer object for data collection.
 
bool m_collect
 flag indicating whether or not data is being collected
 

Constructor & Destructor Documentation

◆ ChPathSteeringControllerXT() [1/2]

chrono::vehicle::ChPathSteeringControllerXT::ChPathSteeringControllerXT ( std::shared_ptr< ChBezierCurve path,
bool  isClosedPath = false,
double  max_wheel_turn_angle = 0.0 
)

Construct a steering controller to track the specified path.

This version uses default controller parameters (zero gains). The user is responsible for calling SetGains and SetLookAheadDistance.

◆ ChPathSteeringControllerXT() [2/2]

chrono::vehicle::ChPathSteeringControllerXT::ChPathSteeringControllerXT ( const std::string &  filename,
std::shared_ptr< ChBezierCurve path,
bool  isClosedPath = false,
double  max_wheel_turn_angle = 0.0 
)

Construct a steering controller to track the specified path.

This version reads controller gains and lookahead distance from the specified JSON file.

Member Function Documentation

◆ CalcTargetLocation()

void chrono::vehicle::ChPathSteeringControllerXT::CalcTargetLocation ( )
overridevirtual

Calculate the current target point location.

The target point is the point on the associated path that is closest to the current location of the sentinel point.

Implements chrono::vehicle::ChSteeringController.

◆ Reset()

void chrono::vehicle::ChPathSteeringControllerXT::Reset ( const ChVehicle vehicle)
overridevirtual

Reset the PID controller.

This function resets the underlying path tracker using the current location of the sentinel point.

Reimplemented from chrono::vehicle::ChSteeringController.


The documentation for this class was generated from the following files:
  • /builds/uwsbel/chrono/src/chrono_vehicle/utils/ChSteeringController.h
  • /builds/uwsbel/chrono/src/chrono_vehicle/utils/ChSteeringController.cpp