Utility classes

Description

Collaboration diagram for Utility classes:

Classes

class  chrono::vehicle::ChAdaptiveSpeedController
 Data collection from the speed controller can be started (restarted) and suspended (stopped) as many times as desired. More...
class  chrono::vehicle::ChSpeedController
 Data collection from the speed controller can be started (restarted) and suspended (stopped) as many times as desired. More...
class  chrono::vehicle::ChSteeringController
 Base class for all steering path-following PID controllers. More...
class  chrono::vehicle::ChPathSteeringController
 Path-following steering PID controller. More...
class  chrono::vehicle::ChPathSteeringControllerXT
 Path-following steering 3(2) channel PDT1/PT1 controller. More...

Functions

 chrono::vehicle::ChPathSteeringControllerSR (std::shared_ptr< ChBezierCurve > path, bool isClosedPath=false, double max_wheel_turn_angle=0.0, double axle_space=2.5)
 Path-following steering P-like controller with variable path prediction.
 chrono::vehicle::ChPathSteeringControllerSR (const std::string &filename, std::shared_ptr< ChBezierCurve > path, bool isClosedPath=false, double max_wheel_turn_angle=0.0, double axle_space=2.5)
 Construct a steering controller to track the specified path.
void chrono::vehicle::SetGains (double Klat=0.1, double Kug=0.0)
void chrono::vehicle::SetPreviewTime (double Tp=0.5)
virtual double chrono::vehicle::Advance (const ChFrameMoving<> &ref_frame, double time, double step) override
 Advance the state of the SR controller.
virtual void chrono::vehicle::Reset (const ChFrameMoving<> &ref_frame) override
 Reset the PID controller.
virtual void chrono::vehicle::CalcTargetLocation () override
 Calculate the current target point location.

Function Documentation

◆ CalcTargetLocation()

virtual void chrono::vehicle::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.

◆ ChPathSteeringControllerSR() [1/2]

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

Construct a steering controller to track the specified path.

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

◆ ChPathSteeringControllerSR() [2/2]

chrono::vehicle::ChPathSteeringControllerSR::ChPathSteeringControllerSR ( std::shared_ptr< ChBezierCurve > path,
bool isClosedPath = false,
double max_wheel_turn_angle = 0.0,
double axle_space = 2.5 )

Path-following steering P-like controller with variable path prediction.

The algorithm is from: M.C. Best, "A simple realistic driver model," AVEC `12: The 11th International Symposium on Advanced Vehicle Control, 9th-12th September 2012, Seoul, Korea. The path to be followed is specified as a ChBezierCurve object and the the original definition points are extracted automatically. Open and closed course definitions can be handled. The ChBezier is still used for visualization. */ class CH_VEHICLE_API ChPathSteeringControllerSR : public ChSteeringController { public: /** 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.

◆ Reset()

virtual void chrono::vehicle::Reset ( const ChFrameMoving<> & ref_frame)
overridevirtual

Reset the PID controller.

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