Description

Base class for chrono wheeled vehicle systems.

This class provides the interface between the vehicle system and other systems (tires, driver, etc.). The reference frame for a vehicle follows the ISO standard: Z-axis up, X-axis pointing forward, and Y-axis towards the left of the vehicle.

#include <ChWheeledVehicle.h>

Inheritance diagram for chrono::vehicle::ChWheeledVehicle:
Collaboration diagram for chrono::vehicle::ChWheeledVehicle:

Public Member Functions

virtual ~ChWheeledVehicle ()
 Destructor.
 
virtual std::string GetTemplateName () const override
 Get the name of the vehicle system template.
 
const ChAxleListGetAxles () const
 Get all vehicle axle subsystems.
 
std::shared_ptr< ChAxleGetAxle (int id) const
 Get the specified vehicle axle subsystem.
 
std::shared_ptr< ChSuspensionGetSuspension (int id) const
 Get the specified suspension subsystem.
 
const ChSteeringListGetSteerings () const
 Get all vehicle steering subsystems.
 
std::shared_ptr< ChSteeringGetSteering (int id) const
 Get the specified steering subsystem.
 
std::shared_ptr< ChWheelGetWheel (int axle, VehicleSide side, WheelLocation location=SINGLE) const
 Get the specified vehicle wheel, by specifying the axle, side, and wheel location. More...
 
std::shared_ptr< ChTireGetTire (int axle, VehicleSide side, WheelLocation location=SINGLE) const
 Get the specified vehicle tire, by specifying the axle, side, and wheel location. More...
 
std::shared_ptr< ChBrakeGetBrake (int axle, VehicleSide side) const
 Get the specified vehicle brake, by specifying the axle and side. More...
 
std::shared_ptr< ChDrivelineWVGetDriveline () const
 Get a handle to the vehicle's driveline subsystem.
 
std::shared_ptr< ChSubchassisGetSubchassis (int id) const
 Get the subchassis system (if none present, returns an empty pointer).
 
virtual int GetNumberAxles () const =0
 Return the number of axles for this vehicle.
 
const ChVectorGetSpindlePos (int axle, VehicleSide side) const
 Get the global location of the specified spindle.
 
ChQuaternion GetSpindleRot (int axle, VehicleSide side) const
 Get the orientation of the specified spindle. More...
 
const ChVectorGetSpindleLinVel (int axle, VehicleSide side) const
 Get the linear velocity of the specified spindle. More...
 
ChVector GetSpindleAngVel (int axle, VehicleSide side) const
 Get the angular velocity of the specified spindle. More...
 
double GetSpindleOmega (int axle, VehicleSide side) const
 Get the angular speed of the specified spindle. More...
 
virtual double GetWheelbase () const =0
 Return the vehicle wheelbase.
 
double GetWheeltrack (int id) const
 Return the vehicle wheel track of the specified suspension subsystem.
 
virtual double GetMinTurningRadius () const
 Return the minimum turning radius. More...
 
virtual double GetMaxSteeringAngle () const
 Return the maximum steering angle. More...
 
void SetSubchassisVisualizationType (VisualizationType vis)
 Set visualization mode for the sub-chassis subsystems.
 
void SetSuspensionVisualizationType (VisualizationType vis)
 Set visualization type for the suspension subsystems. More...
 
void SetSteeringVisualizationType (VisualizationType vis)
 Set visualization type for the steering subsystems. More...
 
void SetWheelVisualizationType (VisualizationType vis)
 Set visualization type for the wheel subsystems. More...
 
void SetTireVisualizationType (VisualizationType vis)
 Set visualization type for the tire subsystems. More...
 
void SetWheelCollide (bool state)
 Enable/disable collision for the wheel subsystems. More...
 
virtual void SetChassisVehicleCollide (bool state) override
 Enable/disable collision between the chassis and all other vehicle subsystems. More...
 
void SetSuspensionOutput (int id, bool state)
 Enable/disable output from the suspension subsystems. More...
 
void SetSteeringOutput (int id, bool state)
 Enable/disable output from the steering subsystems. More...
 
void SetSubchassisOutput (int id, bool state)
 Enable/disable output from the subchassis subsystems. More...
 
void SetAntirollbarOutput (int id, bool state)
 Enable/disable output from the anti-roll bar subsystems. More...
 
void SetDrivelineOutput (bool state)
 Enable/disable output from the driveline subsystem. More...
 
void InitializeTire (std::shared_ptr< ChTire > tire, std::shared_ptr< ChWheel > wheel, VisualizationType tire_vis=VisualizationType::PRIMITIVES, ChTire::CollisionType tire_coll=ChTire::CollisionType::SINGLE_POINT)
 Initialize the given tire and attach it to the specified wheel. More...
 
virtual void InitializeInertiaProperties () override final
 Calculate total vehicle mass. More...
 
virtual void Synchronize (double time, const DriverInputs &driver_inputs)
 Update the state of this vehicle at the current time. More...
 
virtual void Synchronize (double time, const DriverInputs &driver_inputs, const ChTerrain &terrain)
 Update the state of this vehicle at the current time. More...
 
virtual void Advance (double step) override final
 Advance the state of this vehicle by the specified time step. More...
 
void LockAxleDifferential (int axle, bool lock)
 Lock/unlock the differential on the specified axle. More...
 
void LockCentralDifferential (int which, bool lock)
 Lock/unlock the specified central differential. More...
 
void EnableBrakeLocking (bool lock)
 Enable/disable brake locking. More...
 
void ApplyParkingBrake (bool lock)
 Engage/disengage parking brake. More...
 
bool ParkingBrake () const
 Returns the state of the parking brake (true if enagaged, false otherwise).
 
void DisconnectDriveline ()
 Disconnect driveline. More...
 
virtual void LogConstraintViolations () override
 Log current constraint violations.
 
void LogSubsystemTypes ()
 Log the types (template names) of current vehicle subsystems.
 
virtual std::string ExportComponentList () const override
 Return a JSON string with information on all modeling components in the vehicle system. More...
 
virtual void ExportComponentList (const std::string &filename) const override
 Write a JSON-format file with information on all modeling components in the vehicle system. More...
 
- Public Member Functions inherited from chrono::vehicle::ChVehicle
virtual ~ChVehicle ()
 Destructor.
 
const std::string & GetName () const
 Get the name identifier for this vehicle.
 
void SetName (const std::string &name)
 Set the name identifier for this vehicle.
 
ChSystemGetSystem ()
 Get a pointer to the Chrono ChSystem.
 
double GetChTime () const
 Get the current simulation time of the underlying ChSystem.
 
std::shared_ptr< ChChassisGetChassis () const
 Get a handle to the vehicle's main chassis subsystem.
 
std::shared_ptr< ChChassisRearGetChassisRear (int id) const
 Get the specified specified rear chassis subsystem.
 
std::shared_ptr< ChChassisConnectorGetChassisConnector (int id) const
 Get a handle to the specified chassis connector.
 
std::shared_ptr< ChBodyAuxRefGetChassisBody () const
 Get a handle to the vehicle's chassis body.
 
std::shared_ptr< ChBodyAuxRefGetChassisRearBody (int id) const
 Get a handle to the specified rear chassis body.
 
std::shared_ptr< ChPowertrainAssemblyGetPowertrainAssembly () const
 Get the powertrain attached to this vehicle.
 
std::shared_ptr< ChEngineGetEngine () const
 Get the engine in the powertrain assembly (if a powertrain is attached).
 
std::shared_ptr< ChTransmissionGetTransmission () const
 Get the transmission in the powertrain assembly (if a powertrain is attached).
 
double GetMass () const
 Get the vehicle total mass. More...
 
const ChFrameGetCOMFrame () const
 Get the current vehicle COM frame (relative to and expressed in the vehicle reference frame). More...
 
const ChMatrix33GetInertia () const
 Get the current vehicle inertia (relative to the vehicle COM frame).
 
const ChFrameMovingGetRefFrame () const
 Get the current vehicle reference frame. More...
 
const ChFrameGetTransform () const
 Get the current vehicle transform relative to the global frame. More...
 
const ChVectorGetPos () const
 Get the vehicle global location. More...
 
ChQuaternion GetRot () const
 Get the vehicle orientation. More...
 
double GetSpeed () const
 Get the vehicle speed. More...
 
double GetRollRate () const
 Get the vehicle roll rate. More...
 
double GetPitchRate () const
 Get the vehicle pitch rate. More...
 
double GetYawRate () const
 Get the vehicle yaw rate. More...
 
double GetTurnRate () const
 Get the vehicle turn rate. More...
 
ChVector GetPointLocation (const ChVector<> &locpos) const
 Get the global position of the specified point. More...
 
ChVector GetPointVelocity (const ChVector<> &locpos) const
 Get the global velocity of the specified point. More...
 
ChVector GetPointAcceleration (const ChVector<> &locpos) const
 Get the acceleration at the specified point. More...
 
ChVector GetDriverPos () const
 Get the global location of the driver.
 
void EnableRealtime (bool val)
 Enable/disable soft real-time (default: false). More...
 
double GetRTF () const
 Get current estimated RTF (real time factor). More...
 
void SetCollisionSystemType (ChCollisionSystem::Type collsys_type)
 Change the default collision detection system. More...
 
void SetOutput (ChVehicleOutput::Type type, const std::string &out_dir, const std::string &out_name, double output_step)
 Enable output for this vehicle system. More...
 
void SetOutput (ChVehicleOutput::Type type, std::ostream &out_stream, double output_step)
 Enable output for this vehicle system using an existing output stream. More...
 
virtual void Initialize (const ChCoordsys<> &chassisPos, double chassisFwdVel=0)
 Initialize this vehicle at the specified global location and orientation. More...
 
void InitializePowertrain (std::shared_ptr< ChPowertrainAssembly > powertrain)
 Initialize the given powertrain assembly and associate it to this vehicle. More...
 
void SetChassisVisualizationType (VisualizationType vis)
 Set visualization mode for the chassis subsystem.
 
void SetChassisRearVisualizationType (VisualizationType vis)
 Set visualization mode for the rear chassis subsystems.
 
void SetChassisCollide (bool state)
 Enable/disable collision for the chassis subsystem. More...
 
void SetChassisOutput (bool state)
 Enable/disable output from the chassis subsystem.
 
bool HasBushings () const
 Return true if the vehicle model contains bushings.
 

Protected Member Functions

 ChWheeledVehicle (const std::string &name, ChContactMethod contact_method=ChContactMethod::NSC)
 Construct a vehicle system with a default ChSystem. More...
 
 ChWheeledVehicle (const std::string &name, ChSystem *system)
 Construct a vehicle system using the specified ChSystem. More...
 
virtual void UpdateInertiaProperties () override final
 Calculate current vehicle inertia properties. More...
 
virtual void Output (int frame, ChVehicleOutput &database) const override
 Output data for all modeling components in the vehicle system.
 
- Protected Member Functions inherited from chrono::vehicle::ChVehicle
 ChVehicle (const std::string &name, ChContactMethod contact_method=ChContactMethod::NSC)
 Construct a vehicle system with an underlying ChSystem. More...
 
 ChVehicle (const std::string &name, ChSystem *system)
 Construct a vehicle system using the specified ChSystem. More...
 
void SetSystem (ChSystem *sys)
 Set the associated Chrono system.
 

Protected Attributes

ChSubchassisList m_subchassis
 list of subchassis subsystems (typically empty)
 
ChAxleList m_axles
 list of axle subsystems
 
ChSteeringList m_steerings
 list of steering subsystems
 
std::shared_ptr< ChDrivelineWVm_driveline
 driveline subsystem
 
bool m_parking_on
 indicates whether or not parking brake is engaged
 
- Protected Attributes inherited from chrono::vehicle::ChVehicle
std::string m_name
 vehicle name
 
ChSystemm_system
 pointer to the Chrono system
 
bool m_ownsSystem
 true if system created at construction
 
double m_mass
 total vehicle mass
 
ChFrame m_com
 current vehicle COM (relative to the vehicle reference frame)
 
ChMatrix33 m_inertia
 current total vehicle inertia (Relative to the vehicle COM frame)
 
bool m_output
 generate ouput for this vehicle system
 
ChVehicleOutputm_output_db
 vehicle output database
 
double m_output_step
 output time step
 
double m_next_output_time
 time for next output
 
int m_output_frame
 current output frame
 
std::shared_ptr< ChChassism_chassis
 handle to the main chassis subsystem
 
ChChassisRearList m_chassis_rear
 list of rear chassis subsystems (can be empty)
 
ChChassisConnectorList m_chassis_connectors
 list of chassis connector (must match m_chassis_rear)
 
std::shared_ptr< ChPowertrainAssemblym_powertrain_assembly
 associated powertrain system
 

Additional Inherited Members

- Static Protected Member Functions inherited from chrono::vehicle::ChVehicle
template<typename T >
static bool AnyOutput (const std::vector< std::shared_ptr< T >> &list)
 Utility function for testing if any subsystem in a list generates output.
 

Constructor & Destructor Documentation

◆ ChWheeledVehicle() [1/2]

chrono::vehicle::ChWheeledVehicle::ChWheeledVehicle ( const std::string &  name,
ChContactMethod  contact_method = ChContactMethod::NSC 
)
protected

Construct a vehicle system with a default ChSystem.

Parameters
[in]namevehicle name
[in]contact_methodcontact method

◆ ChWheeledVehicle() [2/2]

chrono::vehicle::ChWheeledVehicle::ChWheeledVehicle ( const std::string &  name,
ChSystem system 
)
protected

Construct a vehicle system using the specified ChSystem.

Parameters
[in]namevehicle name
[in]systemcontaining mechanical system

Member Function Documentation

◆ Advance()

void chrono::vehicle::ChWheeledVehicle::Advance ( double  step)
finaloverridevirtual

Advance the state of this vehicle by the specified time step.

In addition to advancing the state of the multibody system (if the vehicle owns the underlying system), this function also advances the state of the associated powertrain and the states of all associated tires.

Reimplemented from chrono::vehicle::ChVehicle.

◆ ApplyParkingBrake()

void chrono::vehicle::ChWheeledVehicle::ApplyParkingBrake ( bool  lock)

Engage/disengage parking brake.

If engaged and supported by the concrete brake type on this vehicle, this locks all vehicle brakes.

◆ DisconnectDriveline()

void chrono::vehicle::ChWheeledVehicle::DisconnectDriveline ( )

Disconnect driveline.

This function has no effect if called before vehicle initialization.

◆ EnableBrakeLocking()

void chrono::vehicle::ChWheeledVehicle::EnableBrakeLocking ( bool  lock)

Enable/disable brake locking.

If supported by the concrete brake type used on this vehicle, the brakes will be locked for large enough braking inputs. By default, brakes do not lock.

◆ ExportComponentList() [1/2]

std::string chrono::vehicle::ChWheeledVehicle::ExportComponentList ( ) const
overridevirtual

Return a JSON string with information on all modeling components in the vehicle system.

These include bodies, shafts, joints, spring-damper elements, markers, etc.

Implements chrono::vehicle::ChVehicle.

◆ ExportComponentList() [2/2]

void chrono::vehicle::ChWheeledVehicle::ExportComponentList ( const std::string &  filename) const
overridevirtual

Write a JSON-format file with information on all modeling components in the vehicle system.

These include bodies, shafts, joints, spring-damper elements, markers, etc.

Implements chrono::vehicle::ChVehicle.

◆ GetBrake()

std::shared_ptr< ChBrake > chrono::vehicle::ChWheeledVehicle::GetBrake ( int  axle,
VehicleSide  side 
) const

Get the specified vehicle brake, by specifying the axle and side.

Axles are assumed to be indexed starting from the front of the vehicle.

◆ GetMaxSteeringAngle()

◆ GetMinTurningRadius()

◆ GetSpindleAngVel()

ChVector chrono::vehicle::ChWheeledVehicle::GetSpindleAngVel ( int  axle,
VehicleSide  side 
) const

Get the angular velocity of the specified spindle.

Return the angular velocity of the spindle frame, expressed in the global reference frame.

◆ GetSpindleLinVel()

const ChVector & chrono::vehicle::ChWheeledVehicle::GetSpindleLinVel ( int  axle,
VehicleSide  side 
) const

Get the linear velocity of the specified spindle.

Return the linear velocity of the spindle center, expressed in the global reference frame.

◆ GetSpindleOmega()

double chrono::vehicle::ChWheeledVehicle::GetSpindleOmega ( int  axle,
VehicleSide  side 
) const

Get the angular speed of the specified spindle.

This is the angular speed of the spindle shaft.

◆ GetSpindleRot()

ChQuaternion chrono::vehicle::ChWheeledVehicle::GetSpindleRot ( int  axle,
VehicleSide  side 
) const

Get the orientation of the specified spindle.

Return a quaternion representing a rotation with respect to the global reference frame.

◆ GetTire()

std::shared_ptr< ChTire > chrono::vehicle::ChWheeledVehicle::GetTire ( int  axle,
VehicleSide  side,
WheelLocation  location = SINGLE 
) const

Get the specified vehicle tire, by specifying the axle, side, and wheel location.

Axles are assumed to be indexed starting from the front of the vehicle. On each axle, wheels are assumed to be ordered from inner to outer wheels, first left then right: for a single-wheel axle the order is left wheel, right wheel; for a double-wheel axle, the order is inner left, inner right, outer left, outer right.

◆ GetWheel()

std::shared_ptr< ChWheel > chrono::vehicle::ChWheeledVehicle::GetWheel ( int  axle,
VehicleSide  side,
WheelLocation  location = SINGLE 
) const

Get the specified vehicle wheel, by specifying the axle, side, and wheel location.

Axles are assumed to be indexed starting from the front of the vehicle. On each axle, wheels are assumed to be ordered from inner to outer wheels, first left then right: for a single-wheel axle the order is left wheel, right wheel; for a double-wheel axle, the order is inner left, inner right, outer left, outer right.

◆ InitializeInertiaProperties()

void chrono::vehicle::ChWheeledVehicle::InitializeInertiaProperties ( )
finaloverridevirtual

Calculate total vehicle mass.

This function is called at the end of the vehicle initialization, but can also be called explicitly.

Implements chrono::vehicle::ChVehicle.

◆ InitializeTire()

void chrono::vehicle::ChWheeledVehicle::InitializeTire ( std::shared_ptr< ChTire tire,
std::shared_ptr< ChWheel wheel,
VisualizationType  tire_vis = VisualizationType::PRIMITIVES,
ChTire::CollisionType  tire_coll = ChTire::CollisionType::SINGLE_POINT 
)

Initialize the given tire and attach it to the specified wheel.

Optionally, specify tire visualization mode and tire-terrain collision detection method. This function should be called only after vehicle initialization.

◆ LockAxleDifferential()

void chrono::vehicle::ChWheeledVehicle::LockAxleDifferential ( int  axle,
bool  lock 
)

Lock/unlock the differential on the specified axle.

By convention, axles are counted front to back, starting with index 0.

◆ LockCentralDifferential()

void chrono::vehicle::ChWheeledVehicle::LockCentralDifferential ( int  which,
bool  lock 
)

Lock/unlock the specified central differential.

By convention, central differentials are counted from front to back, starting with index 0 for the central differential between the two front-most axles.

◆ SetAntirollbarOutput()

void chrono::vehicle::ChWheeledVehicle::SetAntirollbarOutput ( int  id,
bool  state 
)

Enable/disable output from the anti-roll bar subsystems.

See also ChVehicle::SetOuput.

◆ SetChassisVehicleCollide()

void chrono::vehicle::ChWheeledVehicle::SetChassisVehicleCollide ( bool  state)
overridevirtual

Enable/disable collision between the chassis and all other vehicle subsystems.

This only controls collisions between the chassis and the wheel/tire systems.

Reimplemented from chrono::vehicle::ChVehicle.

◆ SetDrivelineOutput()

void chrono::vehicle::ChWheeledVehicle::SetDrivelineOutput ( bool  state)

Enable/disable output from the driveline subsystem.

See also ChVehicle::SetOuput.

◆ SetSteeringOutput()

void chrono::vehicle::ChWheeledVehicle::SetSteeringOutput ( int  id,
bool  state 
)

Enable/disable output from the steering subsystems.

See also ChVehicle::SetOuput.

◆ SetSteeringVisualizationType()

void chrono::vehicle::ChWheeledVehicle::SetSteeringVisualizationType ( VisualizationType  vis)

Set visualization type for the steering subsystems.

This function should be called only after vehicle initialization.

◆ SetSubchassisOutput()

void chrono::vehicle::ChWheeledVehicle::SetSubchassisOutput ( int  id,
bool  state 
)

Enable/disable output from the subchassis subsystems.

See also ChVehicle::SetOuput.

◆ SetSuspensionOutput()

void chrono::vehicle::ChWheeledVehicle::SetSuspensionOutput ( int  id,
bool  state 
)

Enable/disable output from the suspension subsystems.

See also ChVehicle::SetOuput.

◆ SetSuspensionVisualizationType()

void chrono::vehicle::ChWheeledVehicle::SetSuspensionVisualizationType ( VisualizationType  vis)

Set visualization type for the suspension subsystems.

This function should be called only after vehicle initialization.

◆ SetTireVisualizationType()

void chrono::vehicle::ChWheeledVehicle::SetTireVisualizationType ( VisualizationType  vis)

Set visualization type for the tire subsystems.

This function should be called only after vehicle and tire initialization.

◆ SetWheelCollide()

void chrono::vehicle::ChWheeledVehicle::SetWheelCollide ( bool  state)

Enable/disable collision for the wheel subsystems.

This function controls contact of the wheels with all other collision shapes in the simulation.

◆ SetWheelVisualizationType()

void chrono::vehicle::ChWheeledVehicle::SetWheelVisualizationType ( VisualizationType  vis)

Set visualization type for the wheel subsystems.

This function should be called only after vehicle initialization.

◆ Synchronize() [1/2]

void chrono::vehicle::ChWheeledVehicle::Synchronize ( double  time,
const DriverInputs driver_inputs 
)
virtual

Update the state of this vehicle at the current time.

The vehicle system is provided the current driver inputs (throttle between 0 and 1, steering between -1 and +1, braking between 0 and 1). This version does not update any tires associated with the vehicle.

Parameters
[in]timecurrent time
[in]driver_inputscurrent driver inputs

◆ Synchronize() [2/2]

void chrono::vehicle::ChWheeledVehicle::Synchronize ( double  time,
const DriverInputs driver_inputs,
const ChTerrain terrain 
)
virtual

Update the state of this vehicle at the current time.

The vehicle system is provided the current driver inputs (throttle between 0 and 1, steering between -1 and +1, braking between 0 and 1), and a reference to the terrain system. If tires are associated with the vehicle wheels, their Synchronize method is invoked.

Parameters
[in]timecurrent time
[in]driver_inputscurrent driver inputs
[in]terrainreference to the terrain system

◆ UpdateInertiaProperties()

void chrono::vehicle::ChWheeledVehicle::UpdateInertiaProperties ( )
finaloverrideprotectedvirtual

Calculate current vehicle inertia properties.

This function is called at the end of each vehicle state advance.

Implements chrono::vehicle::ChVehicle.


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