AGX Dynamics 2.40.0.0
Loading...
Searching...
No Matches
agxModel::ThreeBodyTire Class Reference

#include <ThreeBodyTire.h>

+ Inheritance diagram for agxModel::ThreeBodyTire:

Public Member Functions

 ThreeBodyTire (agx::RigidBody *tireBodyCollision, agx::RigidBody *tireBodyVisual, agx::Real outerRadius, agx::RigidBody *hubBody, agx::Real innerRadius, const agx::AffineMatrix4x4 &localTransform=agx::AffineMatrix4x4())
 Construct tire given rigid body (with wheel geometry/geometries) and radius.
 
 AGXSTREAM_DECLARE_SERIALIZABLE_BASE (agxModel::ThreeBodyTire)
 
virtual agx::Real getDampingCoefficient (DeformationMode mode) override
 Gets the damping coefficient for a deformation mode.
 
agx::HingegetOuterHinge ()
 Gets the hinge (with active Lock1D) connecting the tire to the hub.
 
virtual agx::Real getStiffness (DeformationMode mode) override
 Gets the stiffness for a deformation mode.
 
const agx::RigidBodygetTireCollisionRigidBody () const
 
agx::RigidBodygetTireVisualRigidBody ()
 
virtual bool setDampingCoefficient (const agx::Real dampingCoefficient, DeformationMode mode) override
 Sets the damping coefficient for a deformation mode.
 
virtual bool setStiffness (const agx::Real stiffness, DeformationMode mode) override
 Sets the stiffness for a deformation mode.
 
- Public Member Functions inherited from agxModel::TwoBodyTire
 TwoBodyTire (agx::RigidBody *tireBody, agx::Real outerRadius, agx::RigidBody *hubBody, agx::Real innerRadius, const agx::AffineMatrix4x4 &localTransform=agx::AffineMatrix4x4())
 Construct tire given rigid body (with wheel geometry/geometries) and radius.
 
 AGXSTREAM_DECLARE_SERIALIZABLE_BASE (agxModel::TwoBodyTire)
 
virtual agx::Real getDampingCoefficient (DeformationMode mode)
 Gets the damping coefficient for a deformation mode.
 
agx::HingegetHinge ()
 Gets the hinge (with active Lock1D) connecting the tire to the hub.
 
agx::RigidBodygetHubRigidBody ()
 
const agx::RigidBodygetHubRigidBody () const
 
agx::Vec2 getImplicitFrictionMultiplier () const
 
agx::Real getInnerRadius () const
 
virtual agx::Real getLoadedRadius () const override
 Gets the current loaded radius.
 
agx::Real getOuterRadius () const
 
const agx::FramegetReferenceFrame () const
 
virtual agx::Real getStiffness (DeformationMode mode)
 Gets the stiffness for a deformation mode.
 
agx::RigidBodygetTireRigidBody ()
 
const agx::RigidBodygetTireRigidBody () const
 
virtual bool isValid () const
 
virtual bool setDampingCoefficient (const agx::Real dampingCoefficient, DeformationMode mode)
 Sets the damping coefficient for a deformation mode.
 
void setImplicitFrictionMultiplier (const agx::Vec2 &implicitFrictionMultiplier)
 Set the implicit friction multiplier in order to get different behavior for different friction directions (forwards, sideways).
 
virtual bool setStiffness (const agx::Real stiffness, DeformationMode mode)
 Sets the stiffness for a deformation mode.
 
- Public Member Functions inherited from agxModel::Tire
virtual agx::Real getLoadedRadius () const
 Gets the current loaded radius.
 
agx::Real getRadius () const
 Gets radius.
 
- Public Member Functions inherited from agxSDK::Assembly
 Assembly ()
 Default constructor.
 
bool add (agx::Constraint *constraint)
 Add a constraint to the assembly.
 
bool add (agx::ContactMaterial *contactMaterial)
 Add a contact material to this assembly.
 
bool add (agx::Emitter *emitter)
 Add an emitter to this assembly.
 
bool add (agx::Interaction *interaction)
 Add an interaction to this assembly.
 
bool add (agx::MergedBody *mergedBody)
 Add a MergedBody to this assembly.
 
bool add (agx::ObserverFrame *observerFrame)
 Add an ObserverFrame to this assembly.
 
bool add (agx::RigidBody *body)
 Add a rigid body to the assembly.
 
bool add (agxCollide::Geometry *geometry)
 Add a geometry to the assembly.
 
bool add (agxSDK::EventListener *listener)
 Add a listener to the assembly.
 
bool add (agxSDK::TerrainInstance *terrainInstance)
 Add a TerrainInstance to this assembly.
 
bool add (agxSDK::TerrainToolInstance *toolInstance)
 Add a TerrainToolInstance to this assembly.
 
bool add (agxStream::Serializable *object)
 Add an object of type serialized.
 
bool add (Assembly *assembly)
 Add another assembly as child to this assembly.
 
virtual void addNotification (agxSDK::Simulation *)
 Called when this assembly is added to a simulation (given that it not already is in the simulation).
 
virtual void addNotification (Assembly *)
 Called when this assembly is added to another assembly.
 
 AGXSTREAM_DECLARE_SERIALIZABLE_BASE (agxSDK::Assembly)
 
size_t collect (agx::ConstraintRefVector &result, bool recursive=true)
 
size_t collect (agx::EmitterRefVector &result, bool recursive=true)
 
size_t collect (agx::InteractionRefVector &result, bool recursive=true)
 
size_t collect (agx::MergedBodyRefVector &result, bool recursive=true)
 
size_t collect (agx::ObserverFrameRefVector &result, bool recursive=true)
 
size_t collect (agx::ParticleSystemRefVector &result, bool recursive=true)
 
size_t collect (agx::RigidBodyRefVector &result, bool recursive=true)
 
size_t collect (agxCollide::GeometryRefVector &result, bool recursive=true)
 
size_t collect (agxSDK::AssemblyRefVector &result, bool recursive=true)
 
size_t collect (agxSDK::EventListenerRefVector &result, bool recursive=true)
 
size_t collect (agxSDK::TerrainInstanceRefVector &result, bool recursive=true)
 
size_t collect (agxSDK::TerrainToolInstanceRefVector &result, bool recursive=true)
 
bool empty () const
 
const AssemblyRefSetVectorgetAssemblies () const
 
agxSDK::AssemblygetAssembly (const agx::Name &name, bool recursive=true)
 Find (linear search) and return named Assembly.
 
const agxSDK::AssemblygetAssembly (const agx::Name &name, bool recursive=true) const
 Find (linear search) and return named Assembly.
 
agxSDK::AssemblygetAssembly (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return an Assembly matching the given uuid.
 
const agxSDK::AssemblygetAssembly (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return an Assembly matching the given uuid.
 
agx::ConstraintgetConstraint (const agx::Name &name, bool recursive=true)
 Find (linear search) and return named Constraint.
 
template<typename T >
T * getConstraint (const agx::Name &name, bool recursive=true)
 Find and return named Constraint of a template type, for example Hinge:
 
const agx::ConstraintgetConstraint (const agx::Name &name, bool recursive=true) const
 Find (linear search) and return named Constraint.
 
template<typename T >
const T * getConstraint (const agx::Name &name, bool recursive=true) const
 Find and return named Constraint of a template type, for example Hinge:
 
agx::ConstraintgetConstraint (const agx::Uuid &uuid, bool recursive=true)
 Find and return a pointer to a Constraint with the given uuid.
 
const agx::ConstraintgetConstraint (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return a pointer to a Constraint with the given uuid.
 
agx::Constraint1DOFgetConstraint1DOF (const agx::Name &name, bool recursive=true)
 
agx::Constraint2DOFgetConstraint2DOF (const agx::Name &name, bool recursive=true)
 
const agx::ConstraintRefSetVectorgetConstraints () const
 
const agx::EmitterRefSetVectorgetEmitters () const
 
const EventListenerRefSetVectorgetEventListeners () const
 
virtual agx::FramegetFrame ()
 Return a reference to the frame containing transformation and velocity information for this assembly.
 
virtual const agx::FramegetFrame () const
 
const agxCollide::GeometryRefSetVectorgetGeometries () const
 
agxCollide::GeometrygetGeometry (const agx::Name &name, bool recursive=true)
 Find (linear search) and return named collision Geometry.
 
const agxCollide::GeometrygetGeometry (const agx::Name &name, bool recursive=true) const
 Find (linear search) and return named collision Geometry.
 
agxCollide::GeometrygetGeometry (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return a Geometry matching the given uuid.
 
const agxCollide::GeometrygetGeometry (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return a Geometry matching the given uuid.
 
const agx::InteractionRefSetVectorgetInteractions () const
 
agx::Vec3 getLocalPosition () const
 
agx::Quat getLocalRotation () const
 
const agx::AffineMatrix4x4getLocalTransform () const
 
const agx::MergedBodyRefSetVectorgetMergedBodies () const
 
agx::MergedBodygetMergedBody (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return an MergedBody matching the given uuid.
 
const agx::MergedBodygetMergedBody (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return an MergedBody matching the given uuid.
 
agx::Name getName () const
 
agx::ObserverFramegetObserverFrame (const agx::Name &name, bool recursive=true)
 Find (linear search) and return an ObserverFrame matching the given uuid.
 
const agx::ObserverFramegetObserverFrame (const agx::Name &name, bool recursive=true) const
 Find (linear search) and return an ObserverFrame matching the given uuid.
 
agx::ObserverFramegetObserverFrame (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return an ObserverFrame matching the given uuid.
 
const agx::ObserverFramegetObserverFrame (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return an ObserverFrame matching the given uuid.
 
const agx::ObserverFrameRefSetVectorgetObserverFrames () const
 
AssemblygetParent ()
 
const AssemblygetParent () const
 
agx::FramegetParentFrame ()
 
const agx::FramegetParentFrame () const
 
const agx::ParticleSystemRefSetVectorgetParticleSystems () const
 
const agx::RigidBodyRefSetVectorgetRigidBodies () const
 
agx::RigidBodygetRigidBody (const agx::Name &name, bool recursive=true)
 Find (linear search) and return named RigidBody.
 
const agx::RigidBodygetRigidBody (const agx::Name &name, bool recursive=true) const
 Find (linear search) and return named RigidBody.
 
agx::RigidBodygetRigidBody (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return a pointer to a RigidBody with the given uuid.
 
const agx::RigidBodygetRigidBody (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return a pointer to a RigidBody with the given uuid.
 
agxSDK::SimulationgetSimulation ()
 
const agxSDK::SimulationgetSimulation () const
 
agxSDK::TerrainInstancegetTerrainInstance (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return an TerrainInstance matching the given uuid.
 
const agxSDK::TerrainInstancegetTerrainInstance (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return an TerrainInstance matching the given uuid.
 
const agxSDK::TerrainInstanceRefSetVectorgetTerrainInstances () const
 
agxSDK::TerrainToolInstancegetTerrainToolInstance (const agx::Uuid &uuid, bool recursive=true)
 Find (linear search) and return an TerrainToolInstance matching the given uuid.
 
const agxSDK::TerrainToolInstancegetTerrainToolInstance (const agx::Uuid &uuid, bool recursive=true) const
 Find (linear search) and return an TerrainToolInstance matching the given uuid.
 
const agxSDK::TerrainToolInstanceRefSetVectorgetTerrainToolInstances () const
 
Type getType () const
 
bool remove (agx::Constraint *constraint)
 Remove a constraint from this assembly (does not recurse down in tree).
 
bool remove (agx::ContactMaterial *contactMaterial)
 Remove a contact material from this assembly.
 
bool remove (agx::Emitter *emitter)
 Remove an emitter from this assembly.
 
bool remove (agx::Interaction *interaction)
 Remove an interaction from this assembly.
 
bool remove (agx::MergedBody *mergedBody)
 Remove a MergedBody from this assembly.
 
bool remove (agx::ObserverFrame *observerFrame, bool resetParentFrame=true)
 Remove an ObserverFrame from this assembly.
 
bool remove (agx::RigidBody *body, bool removeAssociatedGeometries=false, bool resetParentFrame=true)
 Remove a rigid body from this assembly (does not recurse down in tree).
 
bool remove (agxCollide::Geometry *geometry, bool resetParentFrame=true)
 Remove a geometry from this assembly (does not recurse down in tree).
 
bool remove (agxSDK::TerrainInstance *terrainInstance)
 Remove a TerrainInstance from this assembly.
 
bool remove (agxSDK::TerrainToolInstance *toolInstance)
 Remove a TerrainToolInstance from this assembly.
 
bool remove (Assembly *assembly, bool resetParentFrame=true)
 Remove a child assembly from a parent.
 
bool remove (EventListener *listener)
 Remove an EventListener from the assembly.
 
virtual void removeNotification (agxSDK::Simulation *)
 Called when this assembly is removed from a simulation.
 
virtual void removeNotification (Assembly *)
 Called when this assembly is removed from another assembly.
 
bool reset (bool resetParentFrame=true)
 If this assembly is not added to a simulation it will clear all added bodies etc.
 
virtual void setAngularVelocity (const agx::Vec3 &velocity)
 Set the angular velocity (in world frame) recursively for all rigid bodies stored in assembly.
 
void setLocalPosition (agx::Real x, agx::Real y, agx::Real z)
 Set the position of the assembly relative to its frame's parent frame.
 
void setLocalPosition (const agx::Vec3 &p)
 Set the position of the assembly relative to its frame's parent frame.
 
void setLocalRotation (const agx::EulerAngles &e)
 Set the rotation of the assembly relative to its frame's parent frame.
 
void setLocalRotation (const agx::Quat &q)
 Set the rotation of the assembly relative to its frame's parent frame.
 
void setLocalTransform (const agx::AffineMatrix4x4 &matrix)
 Assign the local transformation matrix for this assembly, ignoring any eventual parent transformation.
 
void setName (const agx::Name &name)
 Set the name of this Assembly.
 
bool setParentFrame (agx::Frame *frame)
 Set the parent frame of this assembly's frame.
 
void setPosition (agx::Real x, agx::Real y, agx::Real z)
 Set the position of the frame in world coordinates.
 
void setPosition (const agx::Vec3 &p)
 Set the position of the frame in world coordinates.
 
void setRotation (const agx::EulerAngles &e)
 Set the rotation of the assembly relative to world frame.
 
void setRotation (const agx::OrthoMatrix3x3 &m)
 Set the rotation of the assembly relative to world frame.
 
void setRotation (const agx::Quat &q)
 Set the rotation of the assembly relative to world frame.
 
void setTransform (const agx::AffineMatrix4x4 &matrix)
 Set the transform of the assembly.
 
virtual void setVelocity (const agx::Vec3 &velocity)
 Set the linear velocity (in world frame) recursively for all rigid bodies stored in assembly.
 
bool transfer (agxSDK::Assembly *target)
 Transfer all the content from this assembly to the target, including name and transformation.
 
virtual void traverse (AssemblyVisitor *visitor)
 Traverse the assembly tree recursively using a visitor.
 
virtual void traverse (const AssemblyVisitor *visitor) const
 
- Public Member Functions inherited from agx::Referenced
 Referenced ()
 Default constructor.
 
 Referenced (const Referenced &)
 
template<typename T >
T * as ()
 Subclass casting.
 
template<typename T >
const T * as () const
 
template<typename T >
T * asSafe ()
 Safe subclass casting, return nullptr if template type does not match.
 
template<typename T >
const T * asSafe () const
 
int getReferenceCount () const
 
template<typename T >
bool is () const
 Subclass test.
 
Referencedoperator= (const Referenced &)
 Assignment operator. Will increment the number of references to the referenced object.
 
void reference (void *ptr=nullptr) const
 Explicitly increment the reference count by one, indicating that this object has another pointer which is referencing it.
 
void unreference (void *ptr=nullptr) const
 Decrement the reference count by one, indicating that a pointer to this object is referencing it.
 
void unreference_nodelete () const
 Decrement the reference count by one, indicating that a pointer to this object is referencing it.
 
- Public Member Functions inherited from agxStream::Serializable
virtual ~Serializable ()
 Destructor for normal C++ use but hidden from SWIG bindings.
 
virtual const char * getClassName () const
 
bool getEnableSerialization () const
 
bool getEnableUuidGeneration ()
 
agx::UInt32 getIndex () const
 This index is given at creation of this object.
 
virtual StorageAgent * getStorageAgent () const =0
 
agx::Uuid getUuid () const
 
bool isFinished () const
 
void setEnableSerialization (bool flag)
 Set to false to disable serialization of this object.
 
void setFinished ()
 Tells this class that it is restored correctly and should not be deleted during destruction of an Archive.
 
void setUuid (const agx::Uuid &uuid)
 Explicitly set a Uuid on a serializable object.
 

Static Public Member Functions

static agxStream::Serializablecreate (agxStream::InputArchive &)
 
- Static Public Member Functions inherited from agxModel::TwoBodyTire
static agxStream::Serializablecreate (agxStream::InputArchive &)
 
static TwoBodyTirefind (agxSDK::Assembly *assembly, const agx::Name &name)
 Search the given assembly for a TwoBodyTire with the given name.
 
static TwoBodyTirefind (agxSDK::Simulation *simulation, const agx::Name &name)
 Search the given simulation for a TwoBodyTire with the given name.
 
static TwoBodyTirePtrVector findAll (const agxSDK::Simulation *simulation)
 Finds all TwoBodyTire in the given simulation.
 
static TwoBodyTirePtrVector findAll (const agxSDK::Simulation *simulation, const agx::Name &name)
 Find all TwoBodyTires with given name.
 
- Static Public Member Functions inherited from agxSDK::Assembly
static AssemblyasAssembly (agxStream::Serializable *obj)
 
static agxStream::Serializablecreate (agxStream::InputArchive &)
 
- Static Public Member Functions inherited from agx::Referenced
template<typename T >
static bool ValidateCast (const Referenced *object)
 
- Static Public Member Functions inherited from agxStream::Serializable
static void setEnableUuidGeneration (bool flag)
 Specify if there should be UUID:s generated for each new Serializable object. By default it is enabled.
 

Protected Member Functions

 ThreeBodyTire ()
 
virtual ~ThreeBodyTire ()
 
virtual void addNotification (agxSDK::Simulation *simulation) override
 Called when this assembly is added to a simulation (given that it not already is in the simulation).
 
agxSDK::ContactEventListener::KeepContactPolicy contact (const agx::TimeStamp &, agxCollide::GeometryContact *gc)
 
agxSDK::ContactEventListener::KeepContactPolicy handleContacts (const agx::TimeStamp &, agxCollide::GeometryContact *gc, bool impact)
 
agxSDK::ContactEventListener::KeepContactPolicy impact (const agx::TimeStamp &, agxCollide::GeometryContact *gc)
 
virtual bool isValid () const override
 
virtual void post (const agx::TimeStamp &) override
 
void reduceContacts (agxCollide::LocalGeometryContact &gc)
 
virtual void removeNotification (agxSDK::Simulation *simulation) override
 Called when this assembly is removed from a simulation.
 
void separation (const agx::TimeStamp &, agxCollide::GeometryPair &)
 
- Protected Member Functions inherited from agxModel::TwoBodyTire
 TwoBodyTire ()
 
virtual ~TwoBodyTire ()
 
virtual void addNotification (agxSDK::Simulation *simulation) override
 Called when this assembly is added to a simulation (given that it not already is in the simulation).
 
agxSDK::ContactEventListener::KeepContactPolicy contact (const agx::TimeStamp &, agxCollide::GeometryContact *gc)
 
agx::Vec3 getTireAxisWorld () const
 
agx::Vec3 getTireCenterWorld () const
 
agxSDK::ContactEventListener::KeepContactPolicy handleContacts (const agx::TimeStamp &, agxCollide::GeometryContact *gc)
 
agxSDK::ContactEventListener::KeepContactPolicy impact (const agx::TimeStamp &, agxCollide::GeometryContact *gc)
 
void initBodies (agx::Real outerRadius, agx::Real innerRadius)
 
virtual void last (const agx::TimeStamp &)
 
virtual void post (const agx::TimeStamp &)
 
virtual void pre (const agx::TimeStamp &)
 
virtual void preCollide (const agx::TimeStamp &)
 
void reduceContacts (agxCollide::LocalGeometryContact &gc)
 
virtual void removeNotification (agxSDK::Simulation *simulation) override
 Called when this assembly is removed from a simulation.
 
void separation (const agx::TimeStamp &, agxCollide::GeometryPair &)
 
- Protected Member Functions inherited from agxModel::Tire
 Tire ()
 
virtual ~Tire ()
 
- Protected Member Functions inherited from agxSDK::Assembly
 Assembly (Type type)
 
virtual ~Assembly ()
 Destructor.
 
bool addParticleSystem (agx::ParticleSystem *particleSystem)
 Add a particle system to this assembly.
 
void addToSimulation (Simulation *simulation)
 
void removeFromSimulation (Simulation *simulation)
 
bool removeParticleSystem (agx::ParticleSystem *particleSystem)
 Remove a particle system from this assembly.
 
- Protected Member Functions inherited from agx::Referenced
virtual ~Referenced ()
 Destructor.
 
void allocateObserverVector () const
 
void deleteUsingDeleteHandler () const
 
- Protected Member Functions inherited from agxStream::Serializable
 Serializable ()
 Default constructor.
 
 Serializable (const Serializable &other)
 Copy constructor.
 
void generateUuid ()
 

Protected Attributes

agx::HingeRef m_outerHinge
 
agx::RigidBodyObserver m_tireVisualBody
 
- Protected Attributes inherited from agxModel::TwoBodyTire
agx::UInt32 m_collisionGroup
 
agx::ref_ptr< agxUtil::GeneralContactEventListener< TwoBodyTire > > m_contactCallback
 
agx::Vector< agx::ContactMaterialRefm_contactMaterials
 
agx::Vector< agxCollide::LocalGeometryContactm_contacts
 
agx::HingeRef m_hinge
 
agx::RigidBodyObserver m_hubBody
 
agx::Vec2 m_implicitFrictionMultiplier
 
bool m_initialized
 
agx::Real m_innerRadius
 
agx::Real m_loadedRadius
 
agx::FrameRef m_refFrame
 
agx::ref_ptr< agxUtil::GeneralStepListener< TwoBodyTire > > m_stepCallback
 
agx::RigidBodyObserver m_tireBody
 
- Protected Attributes inherited from agxModel::Tire
agx::Real m_radius
 
- Protected Attributes inherited from agx::Referenced
Mutex m_mutex
 
ObserverContainer m_observers
 
AtomicValue m_refCount
 

Additional Inherited Members

- Public Types inherited from agxModel::TwoBodyTire
enum  DeformationMode { RADIAL , LATERAL , BENDING , TORSIONAL }
 
- Public Types inherited from agxSDK::Assembly
enum  Type { ASSEMBLY , COLLECTION }
 Specifies the type an assembly is. More...
 
- Static Protected Member Functions inherited from agx::Referenced
static DeleteHandlergetDeleteHandler ()
 
static void setDeleteHandler (DeleteHandler *handler)
 Internal: Set a DeleteHandler to which deletion of all referenced counted objects will be delegated to.
 

Detailed Description

Note
: This is an experimental feature, not fully tested yet.

A simple tire model with three rigid bodies - the hub and the tire represented by two bodies. One body with rotational degrees of freedom relative the hub and another with spatial degrees of freedom relative the first tire body. To model any deformation/elastic behavior, the joint settings between hub and tire are being modified.

Notes on stiffness and damping: See TwoBodyTire

Definition at line 38 of file ThreeBodyTire.h.

Constructor & Destructor Documentation

◆ ThreeBodyTire() [1/2]

agxModel::ThreeBodyTire::ThreeBodyTire ( agx::RigidBody tireBodyCollision,
agx::RigidBody tireBodyVisual,
agx::Real  outerRadius,
agx::RigidBody hubBody,
agx::Real  innerRadius,
const agx::AffineMatrix4x4 localTransform = agx::AffineMatrix4x4() 
)

Construct tire given rigid body (with wheel geometry/geometries) and radius.

By definition tire axis is assumed to be y direction in body coordinates. This is also the secondary friction direction. Contacts between the tireBody and the hingeBody will be disabled.

Parameters
tireBodyCollision- rigid body of this tire with spatial degrees of freedom relative the tireBodyVisual (including geometries)
tireBodyVisual- rigid body of this tire with rotational degree of freedom relative the hub (no geometries)
outerRadius- radius of this tire
hubBody- rigid body that the tire is fixed upon (including geometries)
innerRadius- inner radius of the tire (and outer radius of hub)
localTransform- local transform for hinge and friction directions, local in tireBody's coordinate system. Expects rotation axis to be in Y-axis.

◆ ThreeBodyTire() [2/2]

agxModel::ThreeBodyTire::ThreeBodyTire ( )
protected

◆ ~ThreeBodyTire()

virtual agxModel::ThreeBodyTire::~ThreeBodyTire ( )
protectedvirtual

Member Function Documentation

◆ addNotification()

virtual void agxModel::ThreeBodyTire::addNotification ( agxSDK::Simulation )
overrideprotectedvirtual

Called when this assembly is added to a simulation (given that it not already is in the simulation).

Reimplemented from agxModel::TwoBodyTire.

◆ AGXSTREAM_DECLARE_SERIALIZABLE_BASE()

agxModel::ThreeBodyTire::AGXSTREAM_DECLARE_SERIALIZABLE_BASE ( agxModel::ThreeBodyTire  )

◆ contact()

agxSDK::ContactEventListener::KeepContactPolicy agxModel::ThreeBodyTire::contact ( const agx::TimeStamp ,
agxCollide::GeometryContact gc 
)
protected

◆ create()

static agxStream::Serializable * agxModel::ThreeBodyTire::create ( agxStream::InputArchive )
inlinestatic

Definition at line 115 of file ThreeBodyTire.h.

◆ getDampingCoefficient()

virtual agx::Real agxModel::ThreeBodyTire::getDampingCoefficient ( DeformationMode  mode)
overridevirtual

Gets the damping coefficient for a deformation mode.

Parameters
modeThe deformation mode.
Return values
Thedamping Coefficient. 0 if invalid mode.
Note
see comments in class definition about stiffness and damping.

Reimplemented from agxModel::TwoBodyTire.

◆ getOuterHinge()

agx::Hinge * agxModel::ThreeBodyTire::getOuterHinge ( )

Gets the hinge (with active Lock1D) connecting the tire to the hub.

This setup is an implementation detail, and might change in future versions of AGX. Having direct control over the hinge can be helpful in order to change fine-grained options such as compliance and damping. Use with care.

Return values
Thehinge between tire and hub. 0 if isValid is false.

◆ getStiffness()

virtual agx::Real agxModel::ThreeBodyTire::getStiffness ( DeformationMode  mode)
overridevirtual

Gets the stiffness for a deformation mode.

Parameters
modeThe deformation mode.
Return values
Thestiffness. 0 if invalid mode.
Note
see comments in class definition about stiffness and damping.

Reimplemented from agxModel::TwoBodyTire.

◆ getTireCollisionRigidBody()

const agx::RigidBody * agxModel::ThreeBodyTire::getTireCollisionRigidBody ( ) const
Returns
the rigid body of the tire.

◆ getTireVisualRigidBody()

agx::RigidBody * agxModel::ThreeBodyTire::getTireVisualRigidBody ( )
Returns
the rigid body of the tire.

◆ handleContacts()

agxSDK::ContactEventListener::KeepContactPolicy agxModel::ThreeBodyTire::handleContacts ( const agx::TimeStamp ,
agxCollide::GeometryContact gc,
bool  impact 
)
protected

◆ impact()

agxSDK::ContactEventListener::KeepContactPolicy agxModel::ThreeBodyTire::impact ( const agx::TimeStamp ,
agxCollide::GeometryContact gc 
)
protected

◆ isValid()

virtual bool agxModel::ThreeBodyTire::isValid ( ) const
overrideprotectedvirtual
Returns
Is the tire valid?

Reimplemented from agxModel::TwoBodyTire.

◆ post()

virtual void agxModel::ThreeBodyTire::post ( const agx::TimeStamp )
overrideprotectedvirtual

Reimplemented from agxModel::TwoBodyTire.

◆ reduceContacts()

void agxModel::ThreeBodyTire::reduceContacts ( agxCollide::LocalGeometryContact gc)
protected

◆ removeNotification()

virtual void agxModel::ThreeBodyTire::removeNotification ( agxSDK::Simulation )
overrideprotectedvirtual

Called when this assembly is removed from a simulation.

Reimplemented from agxModel::TwoBodyTire.

◆ separation()

void agxModel::ThreeBodyTire::separation ( const agx::TimeStamp ,
agxCollide::GeometryPair &   
)
protected

◆ setDampingCoefficient()

virtual bool agxModel::ThreeBodyTire::setDampingCoefficient ( const agx::Real  dampingCoefficient,
DeformationMode  mode 
)
overridevirtual

Sets the damping coefficient for a deformation mode.

Parameters
dampingCoefficientThe damping Coefficient.
modeThe deformation mode.
Return values
Trueif setting was successful.
Note
see comments in class definition about stiffness and damping.

Reimplemented from agxModel::TwoBodyTire.

◆ setStiffness()

virtual bool agxModel::ThreeBodyTire::setStiffness ( const agx::Real  stiffness,
DeformationMode  mode 
)
overridevirtual

Sets the stiffness for a deformation mode.

Parameters
stiffnessThe stiffness.
modeThe deformation mode.
Return values
Trueif setting was successful.
Note
see comments in class definition about stiffness and damping.

Reimplemented from agxModel::TwoBodyTire.

Member Data Documentation

◆ m_outerHinge

agx::HingeRef agxModel::ThreeBodyTire::m_outerHinge
protected

Definition at line 162 of file ThreeBodyTire.h.

◆ m_tireVisualBody

agx::RigidBodyObserver agxModel::ThreeBodyTire::m_tireVisualBody
protected

Definition at line 161 of file ThreeBodyTire.h.


The documentation for this class was generated from the following file: