Description
"Stanley" path-following ontroller named after an autonomous vehicle called Stanley.
It minimizes lateral error and heading error. Time delay of the driver's reaction is considered. This driver can be parametrized by a PID json file. It can consider a dead zone left and right to the path, where no path information is recognized. This can be useful when the path information contains lateral disturbances, that could cause bad disturbances of the controller. dead_zone = 0.05 means: 0 <= lat_err <= 0.05 no driver reaction 0.05 < lat_err <= 2*0.05 smooth transition interval to complete controller engagement The Stanley driver should find 'always' back to the path, despite of great heading or lateral error. If an integral term is used, its state is getting reset every 30 secs to avoid controller wind-up.
The algorithm comes from from : Gabriel M. Hoffmann, Claire J. Tomlin, Michael Montemerlo, Sebastian Thrun: "Autonomous Automobile Trajectory Tracking for Off-Road Driving", 2005, Stanford University, USA
#include <ChSteeringController.h>
Public Member Functions | |
ChPathSteeringControllerStanley (std::shared_ptr< ChBezierCurve > path, double max_wheel_turn_angle=0.0) | |
Construct a steering controller to track the specified path. More... | |
ChPathSteeringControllerStanley (const std::string &filename, std::shared_ptr< ChBezierCurve > path, double max_wheel_turn_angle=0.0) | |
Construct a steering controller to track the specified path. More... | |
void | SetGains (double Kp, double Ki, double Kd) |
Set the gains for the PID controller. | |
void | SetDeadZone (double dead_zone=0.0) |
virtual double | Advance (const ChVehicle &vehicle, double step) override |
Advance the state of the Stanley controller. | |
virtual void | Reset (const ChVehicle &vehicle) override |
Reset the PID controller. More... | |
virtual void | CalcTargetLocation () override |
Calculate the current target point location. More... | |
double | CalcHeadingError (ChVector<> &a, ChVector<> &b) |
Public Member Functions inherited from chrono::vehicle::ChSteeringController | |
virtual | ~ChSteeringController () |
Destructor. | |
void | SetLookAheadDistance (double dist) |
Specify the look-ahead distance. More... | |
const ChVector & | GetSentinelLocation () const |
Return the current location of the sentinel point. More... | |
const ChVector & | GetTargetLocation () const |
Return the current value of the target point. More... | |
std::shared_ptr< ChBezierCurve > | GetPath () const |
Return a pointer to the Bezier curve. | |
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 Member Functions inherited from chrono::vehicle::ChSteeringController | |
ChSteeringController (std::shared_ptr< ChBezierCurve > path) | |
Construct a steering controller with default parameters. | |
Protected Attributes inherited from chrono::vehicle::ChSteeringController | |
std::shared_ptr< ChBezierCurve > | m_path |
tracked path (piecewise cubic Bezier curve) | |
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_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
◆ ChPathSteeringControllerStanley() [1/2]
chrono::vehicle::ChPathSteeringControllerStanley::ChPathSteeringControllerStanley | ( | std::shared_ptr< ChBezierCurve > | path, |
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.
◆ ChPathSteeringControllerStanley() [2/2]
chrono::vehicle::ChPathSteeringControllerStanley::ChPathSteeringControllerStanley | ( | const std::string & | filename, |
std::shared_ptr< ChBezierCurve > | path, | ||
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()
|
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()
|
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