Description
Sedan vehicle system.
#include <Cherokee_Vehicle.h>
Public Member Functions | |
Cherokee_Vehicle (const bool fixed, BrakeType brake_type, ChContactMethod contact_method=ChContactMethod::NSC, CollisionType chassis_collision_type=CollisionType::NONE) | |
Cherokee_Vehicle (ChSystem *system, const bool fixed, BrakeType brake_type, CollisionType chassis_collision_type=CollisionType::NONE) | |
virtual unsigned int | GetNumberAxles () const override |
Return the number of axles for this vehicle. | |
virtual double | GetWheelbase () const override |
Return the vehicle wheelbase. | |
virtual double | GetMinTurningRadius () const override |
Return the minimum turning radius. More... | |
virtual double | GetMaxSteeringAngle () const override |
Return the maximum steering angle. More... | |
void | SetInitWheelAngVel (const std::vector< double > &omega) |
double | GetSpringForce (int axle, VehicleSide side) const |
double | GetSpringLength (int axle, VehicleSide side) const |
double | GetSpringDeformation (int axle, VehicleSide side) const |
double | GetShockForce (int axle, VehicleSide side) const |
double | GetShockLength (int axle, VehicleSide side) const |
double | GetShockVelocity (int axle, VehicleSide side) const |
virtual void | Initialize (const ChCoordsys<> &chassisPos, double chassisFwdVel=0) override |
Initialize this vehicle at the specified global location and orientation. More... | |
void | LogHardpointLocations () |
void | DebugLog (int what) |
suspension hardpoints at design | |
Public Member Functions inherited from chrono::vehicle::ChWheeledVehicle | |
virtual | ~ChWheeledVehicle () |
Destructor. | |
virtual std::string | GetTemplateName () const override |
Get the name of the vehicle system template. | |
const ChAxleList & | GetAxles () const |
Get all vehicle axle subsystems. | |
std::shared_ptr< ChAxle > | GetAxle (int id) const |
Get the specified vehicle axle subsystem. | |
std::shared_ptr< ChSuspension > | GetSuspension (int id) const |
Get the specified suspension subsystem. | |
const ChSteeringList & | GetSteerings () const |
Get all vehicle steering subsystems. | |
std::shared_ptr< ChSteering > | GetSteering (int id) const |
Get the specified steering subsystem. | |
std::shared_ptr< ChWheel > | GetWheel (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< ChTire > | GetTire (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< ChBrake > | GetBrake (int axle, VehicleSide side) const |
Get the specified vehicle brake, by specifying the axle and side. More... | |
std::shared_ptr< ChDrivelineWV > | GetDriveline () const |
Get a handle to the vehicle's driveline subsystem. | |
std::shared_ptr< ChSubchassis > | GetSubchassis (int id) const |
Get the subchassis system (if none present, returns an empty pointer). | |
const ChVector3d & | GetSpindlePos (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 ChVector3d & | GetSpindleLinVel (int axle, VehicleSide side) const |
Get the linear velocity of the specified spindle. More... | |
ChVector3d | 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... | |
double | GetSteeringAngle (int axle, VehicleSide side) const |
Get the current steering angle of the specified wheel/spindle. More... | |
double | GetWheeltrack (int id) const |
Return the vehicle wheel track of the specified suspension subsystem. | |
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. | |
ChSystem * | GetSystem () |
Get a pointer to the Chrono ChSystem. | |
double | GetChTime () const |
Get the current simulation time of the underlying ChSystem. | |
std::shared_ptr< ChChassis > | GetChassis () const |
Get a handle to the vehicle's main chassis subsystem. | |
std::shared_ptr< ChChassisRear > | GetChassisRear (int id) const |
Get the specified specified rear chassis subsystem. | |
std::shared_ptr< ChChassisConnector > | GetChassisConnector (int id) const |
Get a handle to the specified chassis connector. | |
std::shared_ptr< ChBodyAuxRef > | GetChassisBody () const |
Get a handle to the vehicle's chassis body. | |
std::shared_ptr< ChBodyAuxRef > | GetChassisRearBody (int id) const |
Get a handle to the specified rear chassis body. | |
std::shared_ptr< ChPowertrainAssembly > | GetPowertrainAssembly () const |
Get the powertrain attached to this vehicle. | |
std::shared_ptr< ChEngine > | GetEngine () const |
Get the engine in the powertrain assembly (if a powertrain is attached). | |
std::shared_ptr< ChTransmission > | GetTransmission () const |
Get the transmission in the powertrain assembly (if a powertrain is attached). | |
double | GetMass () const |
Get the vehicle total mass. More... | |
const ChFrame & | GetCOMFrame () const |
Get the current vehicle COM frame (relative to and expressed in the vehicle reference frame). More... | |
const ChMatrix33 & | GetInertia () const |
Get the current vehicle inertia (relative to the vehicle COM frame). | |
const ChFrameMoving & | GetRefFrame () const |
Get the current vehicle reference frame. More... | |
const ChFrame & | GetTransform () const |
Get the current vehicle transform relative to the global frame. More... | |
const ChVector3d & | GetPos () const |
Get the vehicle global location. More... | |
ChQuaternion | GetRot () const |
Get the vehicle orientation. More... | |
double | GetRoll () const |
Get vehicle roll angle. More... | |
double | GetPitch () const |
Get vehicle pitch angle. More... | |
double | GetRoll (const ChTerrain &terrain) const |
Get vehicle roll angle (relative to local terrain). More... | |
double | GetPitch (const ChTerrain &terrain) const |
Get vehicle pitch angle (relative to local terrain). More... | |
double | GetSpeed () const |
Get the vehicle speed (velocity component in the vehicle forward direction). More... | |
double | GetSlipAngle () const |
Get the vehicle slip angle. 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... | |
ChVector3d | GetPointLocation (const ChVector3d &locpos) const |
Get the global position of the specified point. More... | |
ChVector3d | GetPointVelocity (const ChVector3d &locpos) const |
Get the global velocity of the specified point. More... | |
ChVector3d | GetPointAcceleration (const ChVector3d &locpos) const |
Get the acceleration at the specified point. More... | |
ChVector3d | 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... | |
double | GetStepRTF () const |
Get current estimated step 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... | |
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. | |
Additional Inherited Members | |
Protected Member Functions inherited from chrono::vehicle::ChWheeledVehicle | |
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. | |
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. | |
Protected Attributes inherited from chrono::vehicle::ChWheeledVehicle | |
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< ChDrivelineWV > | m_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 | |
ChSystem * | m_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 | |
ChVehicleOutput * | m_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< ChChassis > | m_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< ChPowertrainAssembly > | m_powertrain_assembly |
associated powertrain system | |
Member Function Documentation
◆ GetMaxSteeringAngle()
|
inlineoverridevirtual |
Return the maximum steering angle.
This default implementation estimates the maximum steering angle based on a bicycle model and the vehicle minimum turning radius.
Reimplemented from chrono::vehicle::ChWheeledVehicle.
◆ GetMinTurningRadius()
|
inlineoverridevirtual |
Return the minimum turning radius.
A concrete wheeled vehicle class should override the default value (20 m).
Reimplemented from chrono::vehicle::ChWheeledVehicle.
◆ Initialize()
|
overridevirtual |
Initialize this vehicle at the specified global location and orientation.
Derived classes must invoke this base class implementation after they initialize all their subsystem.
- Parameters
-
[in] chassisPos initial global position and orientation [in] chassisFwdVel initial chassis forward velocity
Reimplemented from chrono::vehicle::ChVehicle.
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono_models/vehicle/jeep/Cherokee_Vehicle.h
- /builds/uwsbel/chrono/src/chrono_models/vehicle/jeep/Cherokee_Vehicle.cpp