Description
Create rigid bodies with a convex hull shape.
Optionally sets the visualization and/or collision geometry and automatically calculates intertia properties based on the geometry.
#include <ChBodyEasy.h>


| Public Member Functions | |
| ChBodyEasyConvexHull (std::vector< ChVector3d > &points, double density, bool create_visualization=true, bool create_collision=false, std::shared_ptr< ChContactMaterial > material=nullptr) | |
| Create a rigid body with optional convex hull visualization and/or collision shape.  More... | |
| ChBodyEasyConvexHull (std::vector< ChVector3d > &points, double density, std::shared_ptr< ChContactMaterial > material) | |
| Create a rigid body with a convex hull visualization and collision shape.  More... | |
| std::shared_ptr< ChTriangleMeshConnected > | GetMesh () const | 
| virtual void | ArchiveOutConstructor (ChArchiveOut &archive_out) | 
| Deserialization for non-default constructor classes. | |
|  Public Member Functions inherited from chrono::ChBody | |
| ChBody (const ChBody &other) | |
| virtual ChBody * | Clone () const override | 
| "Virtual" copy constructor (covariant return type). | |
| void | SetFixed (bool state) | 
| Sets the 'fixed' state of the body.  More... | |
| bool | IsFixed () const | 
| Return true if this body is fixed to ground. | |
| void | EnableCollision (bool state) | 
| Enable/disable the collision for this rigid body. | |
| virtual bool | IsCollisionEnabled () const override | 
| Return true if collision is enabled for this body. | |
| void | SetLimitSpeed (bool state) | 
| Enable the maximum linear speed limit (default: false). | |
| void | SetUseGyroTorque (bool state) | 
| Enable/disable the gyroscopic torque (quadratic term).  More... | |
| bool | IsUsingGyroTorque () const | 
| Return true if gyroscopic torque is used (default=true). | |
| void | SetSleepingAllowed (bool state) | 
| Enable/disable option for setting bodies to 'sleep'.  More... | |
| bool | IsSleepingAllowed () const | 
| Return true if 'sleep' mode is allowed for this specific body. | |
| void | SetSleeping (bool state) | 
| Force the body in sleeping mode or not.  More... | |
| bool | IsSleeping () const | 
| Return true if this body is currently in 'sleep' mode. | |
| bool | TrySleeping () | 
| Test if a body could go in sleeping state if requirements are satisfied.  More... | |
| virtual bool | IsActive () const override | 
| Return true if the body is currently active and therefore included into the system solver.  More... | |
| unsigned int | GetIndex () | 
| Get the unique sequential body index (internal use only). | |
| virtual unsigned int | GetNumCoordsPosLevel () override | 
| Number of coordinates of body: 7 because uses quaternions for rotation. | |
| virtual unsigned int | GetNumCoordsVelLevel () override | 
| Number of coordinates of body: 6 because derivatives use angular velocity. | |
| virtual ChVariables & | Variables () override | 
| Return a reference to the encapsulated ChVariablesBody, representing states (pos, speed, or accel.) and forces.  More... | |
| void | ForceToRest () override | 
| Set no speed and no accelerations (but does not change the position). | |
| virtual void | AddCollisionModelsToSystem (ChCollisionSystem *coll_sys) const override | 
| Add the body collision model (if any) to the provided collision system. | |
| virtual void | RemoveCollisionModelsFromSystem (ChCollisionSystem *coll_sys) const override | 
| Remove the body collision model (if any) from the provided collision system. | |
| virtual void | SyncCollisionModels () override | 
| Synchronize the position and bounding box of the body collision model (if any). | |
| virtual const ChFrameMoving & | GetFrameCOMToAbs () const | 
| Get the rigid body coordinate system that represents the GOG (Center of Gravity).  More... | |
| virtual const ChFrameMoving & | GetFrameRefToAbs () const | 
| Get the rigid body coordinate system that is used for defining the collision shapes and the ChMarker objects.  More... | |
| virtual ChFrame | GetVisualModelFrame (unsigned int nclone=0) const override | 
| Get the reference frame (expressed in and relative to the absolute frame) of the visual model.  More... | |
| virtual ChAABB | GetTotalAABB () const override | 
| Get the axis-aligned bounding (AABB) box of the object.  More... | |
| void | AddMarker (std::shared_ptr< ChMarker > amarker) | 
| Attach a marker to this body. | |
| void | AddForce (std::shared_ptr< ChForce > aforce) | 
| Attach a force to this body. | |
| void | RemoveMarker (std::shared_ptr< ChMarker > amarker) | 
| Remove a specific marker from this body.  More... | |
| void | RemoveForce (std::shared_ptr< ChForce > aforce) | 
| Remove a specific force from this body.  More... | |
| void | RemoveAllForces () | 
| Remove all markers at once.  More... | |
| void | RemoveAllMarkers () | 
| Remove all markers at once.  More... | |
| std::shared_ptr< ChMarker > | SearchMarker (const std::string &name) const | 
| Find a marker by its name. | |
| std::shared_ptr< ChMarker > | SearchMarker (int id) const | 
| Find a marker by its identifier. | |
| std::shared_ptr< ChForce > | SearchForce (const std::string &name) const | 
| Find a force by its name. | |
| const std::vector< std::shared_ptr< ChMarker > > & | GetMarkers () const | 
| Gets the list of children markers.  More... | |
| const std::vector< std::shared_ptr< ChForce > > & | GetForces () const | 
| Gets the list of children forces.  More... | |
| void | SetMass (double newmass) | 
| Set the body mass.  More... | |
| double | GetMass () | 
| Get the body mass. | |
| void | SetInertia (const ChMatrix33<> &newXInertia) | 
| Set the inertia tensor of the body.  More... | |
| const ChMatrix33 & | GetInertia () const | 
| Get the inertia tensor, expressed in the local coordinate system.  More... | |
| const ChMatrix33 & | GetInvInertia () const | 
| Get the inverse of the inertia matrix. | |
| void | SetInertiaXX (const ChVector3d &iner) | 
| Set the diagonal part of the inertia tensor (Ixx, Iyy, Izz values).  More... | |
| ChVector3d | GetInertiaXX () const | 
| Get the diagonal part of the inertia tensor (Ixx, Iyy, Izz values).  More... | |
| void | SetInertiaXY (const ChVector3d &iner) | 
| Set the off-diagonal part of the inertia tensor (Ixy, Ixz, Iyz values).  More... | |
| ChVector3d | GetInertiaXY () const | 
| Get the extra-diagonal part of the inertia tensor (Ixy, Ixz, Iyz values).  More... | |
| void | SetMaxLinVel (float m_max_speed) | 
| Set the maximum linear speed (beyond this limit it will be clamped).  More... | |
| float | GetMaxLinVel () const | 
| void | SetMaxAngVel (float m_max_wvel) | 
| Set the maximum angular speed (beyond this limit it will be clamped).  More... | |
| float | GetMaxAngVel () const | 
| void | ClampSpeed () | 
| Clamp the body speed to the provided limits.  More... | |
| void | SetSleepTime (float m_t) | 
| Set the amount of time which must pass before going automatically in sleep mode when the body has very small movements. | |
| float | GetSleepTime () const | 
| void | SetSleepMinLinVel (float m_t) | 
| Set the max linear speed to be kept for 'sleep_time' before freezing. | |
| float | GetSleepMinLinVel () const | 
| void | SetSleepMinAngVel (float m_t) | 
| Set the max linear speed to be kept for 'sleep_time' before freezing. | |
| float | GetSleepMinAngVel () const | 
| void | ComputeQInertia (ChMatrix44<> &mQInertia) | 
| Computes the 4x4 inertia tensor in quaternion space, if needed. | |
| void | ComputeGyro () | 
| Computes the gyroscopic torque.  More... | |
| unsigned int | AddAccumulator () | 
| Add a new force and torque accumulator.  More... | |
| void | EmptyAccumulator (unsigned int idx) | 
| Clear the accumulator with specififed index. | |
| void | AccumulateForce (unsigned int idx, const ChVector3d &force, const ChVector3d &appl_point, bool local) | 
| Include a concentrated body force in the specified accumulator.  More... | |
| void | AccumulateTorque (unsigned int idx, const ChVector3d &torque, bool local) | 
| Include a body torque in the specified accumulator.  More... | |
| const ChVector3d & | GetAccumulatedForce (unsigned int idx) const | 
| Return the current value of the accumulated force from the specified accumulator.  More... | |
| const ChVector3d & | GetAccumulatedTorque (unsigned int idx) const | 
| Return the current value of the accumulated torque from the specified accumulator.  More... | |
| const ChWrenchd | GetAccumulatorWrench () const | 
| void | UpdateMarkers (double time, bool update_assets) | 
| Update all children markers of the rigid body, at current body state. | |
| void | UpdateForces (double time, bool update_assets) | 
| Update all children forces of the rigid body, at current body state. | |
| virtual void | Update (double time, bool update_assets) override | 
| Update all auxiliary data of the rigid body and of its children (markers, forces..), at given time. | |
| ChVector3d | GetAppliedForce () | 
| Return the resultant applied force on the body.  More... | |
| ChVector3d | GetAppliedTorque () | 
| Return the resultant applied torque on the body.  More... | |
| ChVector3d | GetContactForce () | 
| Get the resultant contact force acting on this body. | |
| ChVector3d | GetContactTorque () | 
| Get the resultant contact torque acting on this body. | |
| virtual ChPhysicsItem * | GetPhysicsItem () override | 
| This is only for backward compatibility. | |
| virtual void | ArchiveOut (ChArchiveOut &archive_out) override | 
| Method to allow serialization of transient data to archives. | |
| virtual void | ArchiveIn (ChArchiveIn &archive_in) override | 
| Method to allow deserialization of transient data from archives.  More... | |
| virtual void | LoadableGetVariables (std::vector< ChVariables * > &mvars) override | 
| Get the pointers to the contained ChVariables, appending to the mvars vector. | |
| virtual void | LoadableStateIncrement (const unsigned int off_x, ChState &x_new, const ChState &x, const unsigned int off_v, const ChStateDelta &Dv) override | 
| Increment all DOFs using a delta. | |
| virtual void | LoadableGetStateBlockPosLevel (int block_offset, ChState &mD) override | 
| Gets all the DOFs packed in a single vector (position part) | |
| virtual void | LoadableGetStateBlockVelLevel (int block_offset, ChStateDelta &mD) override | 
| Gets all the DOFs packed in a single vector (speed part) | |
| virtual void | ComputeNF (const double U, const double V, const double W, ChVectorDynamic<> &Qi, double &detJ, const ChVectorDynamic<> &F, ChVectorDynamic<> *state_x, ChVectorDynamic<> *state_w) override | 
| Evaluate Q=N'*F, for Q generalized lagrangian load, where N is some type of matrix evaluated at point P(U,V,W) assumed in absolute coordinates, and F is a load assumed in absolute coordinates.  More... | |
|  Public Member Functions inherited from chrono::ChPhysicsItem | |
| ChPhysicsItem (const ChPhysicsItem &other) | |
| ChSystem * | GetSystem () const | 
| Get the pointer to the parent ChSystem(). | |
| virtual void | SetSystem (ChSystem *m_system) | 
| Set the pointer to the parent ChSystem().  More... | |
| virtual ChVector3d | GetCenter () const | 
| Get a symbolic 'center' of the object.  More... | |
| virtual void | Setup () | 
| Perform setup operations.  More... | |
| virtual unsigned int | GetNumConstraints () | 
| Get the number of scalar constraints. | |
| virtual unsigned int | GetNumConstraintsBilateral () | 
| Get the number of bilateral scalar constraints. | |
| virtual unsigned int | GetNumConstraintsUnilateral () | 
| Get the number of unilateral scalar constraints. | |
| unsigned int | GetOffset_x () | 
| Get offset in the state vector (position part) | |
| unsigned int | GetOffset_w () | 
| Get offset in the state vector (speed part) | |
| unsigned int | GetOffset_L () | 
| Get offset in the lagrangian multipliers. | |
| void | SetOffset_x (const unsigned int moff) | 
| Set offset in the state vector (position part) Note: only the ChSystem::Setup function should use this. | |
| void | SetOffset_w (const unsigned int moff) | 
| Set offset in the state vector (speed part) Note: only the ChSystem::Setup function should use this. | |
| void | SetOffset_L (const unsigned int moff) | 
| Set offset in the lagrangian multipliers Note: only the ChSystem::Setup function should use this. | |
| virtual void | IntStateGatherReactions (const unsigned int off_L, ChVectorDynamic<> &L) | 
| From item's reaction forces to global reaction vector.  More... | |
| virtual void | IntStateScatterReactions (const unsigned int off_L, const ChVectorDynamic<> &L) | 
| From global reaction vector to item's reaction forces.  More... | |
| virtual void | IntLoadResidual_CqL (const unsigned int off_L, ChVectorDynamic<> &R, const ChVectorDynamic<> &L, const double c) | 
| Takes the term Cq'*L, scale and adds to R at given offset: R += c*Cq'*L.  More... | |
| virtual void | IntLoadConstraint_C (const unsigned int off, ChVectorDynamic<> &Qc, const double c, bool do_clamp, double recovery_clamp) | 
| Takes the term C, scale and adds to Qc at given offset: Qc += c*C.  More... | |
| virtual void | IntLoadConstraint_Ct (const unsigned int off, ChVectorDynamic<> &Qc, const double c) | 
| Takes the term Ct, scale and adds to Qc at given offset: Qc += c*Ct.  More... | |
| virtual void | InjectConstraints (ChSystemDescriptor &descriptor) | 
| Register with the given system descriptor any ChConstraint objects associated with this item. | |
| virtual void | LoadConstraintJacobians () | 
| Compute and load current Jacobians in encapsulated ChConstraint objects. | |
| virtual void | InjectKRMMatrices (ChSystemDescriptor &descriptor) | 
| Register with the given system descriptor any ChKRMBlock objects associated with this item. | |
| virtual void | LoadKRMMatrices (double Kfactor, double Rfactor, double Mfactor) | 
| Compute and load current stiffnes (K), damping (R), and mass (M) matrices in encapsulated ChKRMBlock objects.  More... | |
| virtual void | ConstraintsBiReset () | 
| Sets to zero the known term (b_i) of encapsulated ChConstraints. | |
| virtual void | ConstraintsBiLoad_C (double factor=1, double recovery_clamp=0.1, bool do_clamp=false) | 
| Adds the current C (constraint violation) to the known term (b_i) of encapsulated ChConstraints. | |
| virtual void | ConstraintsBiLoad_Ct (double factor=1) | 
| Adds the current Ct (partial t-derivative, as in C_dt=0-> [Cq]*q_dt=-Ct) to the known term (b_i) of encapsulated ChConstraints. | |
| virtual void | ConstraintsBiLoad_Qc (double factor=1) | 
| Adds the current Qc (the vector of C_dtdt=0 -> [Cq]*q_dtdt=Qc ) to the known term (b_i) of encapsulated ChConstraints. | |
| virtual void | ConstraintsFbLoadForces (double factor=1) | 
| Adds the current link-forces, if any, (caused by springs, etc.) to the 'fb' vectors of the ChVariables referenced by encapsulated ChConstraints. | |
| virtual void | ConstraintsFetch_react (double factor=1) | 
| Fetches the reactions from the lagrangian multiplier (l_i) of encapsulated ChConstraints.  More... | |
|  Public Member Functions inherited from chrono::ChObj | |
| ChObj (const ChObj &other) | |
| int | GetIdentifier () const | 
| Get the unique integer identifier of this object.  More... | |
| void | SetTag (int tag) | 
| Set an object integer tag (default: -1).  More... | |
| int | GetTag () const | 
| Get the tag of this object. | |
| void | SetName (const std::string &myname) | 
| Set the name of this object. | |
| const std::string & | GetName () const | 
| Get the name of this object. | |
| double | GetChTime () const | 
| Gets the simulation time of this object. | |
| void | SetChTime (double m_time) | 
| Sets the simulation time of this object. | |
| void | AddVisualModel (std::shared_ptr< ChVisualModel > model) | 
| Add an (optional) visualization model.  More... | |
| std::shared_ptr< ChVisualModel > | GetVisualModel () const | 
| Access the visualization model (if any).  More... | |
| void | AddVisualShape (std::shared_ptr< ChVisualShape > shape, const ChFrame<> &frame=ChFrame<>()) | 
| Add the specified visual shape to the visualization model.  More... | |
| std::shared_ptr< ChVisualShape > | GetVisualShape (unsigned int i) const | 
| Access the specified visualization shape in the visualization model (if any).  More... | |
| void | AddVisualShapeFEA (std::shared_ptr< ChVisualShapeFEA > shapeFEA) | 
| Add the specified FEA visualization object to the visualization model.  More... | |
| std::shared_ptr< ChVisualShapeFEA > | GetVisualShapeFEA (unsigned int i) const | 
| Access the specified FEA visualization object in the visualization model (if any).  More... | |
| virtual unsigned int | GetNumVisualModelClones () const | 
| Return the number of clones of the visual model associated with this object.  More... | |
| void | AddCamera (std::shared_ptr< ChCamera > camera) | 
| Attach a camera to this object.  More... | |
| std::vector< std::shared_ptr< ChCamera > > | GetCameras () const | 
| Get the set of cameras attached to this object. | |
| void | UpdateVisualModel () | 
| Utility function to update only the associated visual assets (if any). | |
| virtual std::string & | ArchiveContainerName () | 
|  Public Member Functions inherited from chrono::ChBodyFrame | |
| ChBodyFrame (const ChBodyFrame &other) | |
| ChWrenchd | AppliedForceLocalToWrenchParent (const ChVector3d &force, const ChVector3d &appl_point) | 
| Transform a force applied to a point on the body to a force and moment at the frame origin.  More... | |
| ChWrenchd | AppliedForceParentToWrenchParent (const ChVector3d &force, const ChVector3d &appl_point) | 
| Transform a force applied to a point on the body to a force and moment at the frame origin.  More... | |
|  Public Member Functions inherited from chrono::ChFrameMoving< double > | |
| ChFrameMoving () | |
| Default constructor (identity frame). | |
| ChFrameMoving (const ChVector3< double > &v, const ChQuaternion< double > &q=ChQuaternion< double >(1, 0, 0, 0)) | |
| Construct from pos and rot (as a quaternion). | |
| ChFrameMoving (const ChVector3< double > &v, const ChMatrix33< double > &R) | |
| Construct from pos and rotation (as a 3x3 matrix). | |
| ChFrameMoving (const ChCoordsys< double > &C) | |
| Construct from a coordsys. | |
| ChFrameMoving (const ChFrame< double > &F) | |
| Construct from a frame. | |
| ChFrameMoving (const ChFrameMoving< double > &other) | |
| Copy constructor, build from another moving frame. | |
| virtual | ~ChFrameMoving () | 
| Destructor. | |
| ChFrameMoving< double > & | operator= (const ChFrameMoving< double > &other) | 
| Assignment operator: copy from another moving frame. | |
| ChFrameMoving< double > & | operator= (const ChFrame< double > &other) | 
| Assignment operator: copy from another frame. | |
| bool | operator== (const ChFrameMoving< double > &other) const | 
| Returns true for identical frames. | |
| bool | operator!= (const ChFrameMoving< double > &other) const | 
| Returns true for different frames. | |
| ChFrameMoving< double > | operator>> (const ChFrameMoving< double > &F) const | 
| Transform another frame through this frame.  More... | |
| ChFrameMoving< double > | operator* (const ChFrameMoving< double > &F) const | 
| Transform another frame through this frame.  More... | |
| ChFrameMoving< double > & | operator>>= (const ChFrameMoving< double > &F) | 
| Transform this frame by pre-multiplication with another frame.  More... | |
| ChFrameMoving< double > & | operator>>= (const ChVector3< double > &v) | 
| Transform this frame by pre-multiplication with a given vector (translate frame). | |
| ChFrameMoving< double > & | operator>>= (const ChQuaternion< double > &q) | 
| Transform this frame by pre-multiplication with a given quaternion (rotate frame). | |
| ChFrameMoving< double > & | operator>>= (const ChCoordsys< double > &C) | 
| Transform this frame by pre-multiplication with a given coordinate system. | |
| ChFrameMoving< double > & | operator>>= (const ChFrame< double > &F) | 
| Transform this frame by pre-multiplication with another frame. | |
| ChFrameMoving< double > & | operator*= (const ChFrameMoving< double > &F) | 
| Transform this frame by post-multiplication with another frame.  More... | |
| const ChCoordsys< double > & | GetCoordsysDt () const | 
| Return both rotation and translation velocities as a ChCoordsys object. | |
| const ChCoordsys< double > & | GetCoordsysDt2 () const | 
| Return both rotation and translation accelerations as a ChCoordsys object. | |
| const ChVector3< double > & | GetPosDt () const | 
| Return the linear velocity. | |
| const ChVector3< double > & | GetLinVel () const | 
| Return the linear velocity. | |
| const ChVector3< double > & | GetPosDt2 () const | 
| Return the linear acceleration. | |
| const ChVector3< double > & | GetLinAcc () const | 
| Return the linear acceleration. | |
| const ChQuaternion< double > & | GetRotDt () const | 
| Return the rotation velocity as a quaternion. | |
| const ChQuaternion< double > & | GetRotDt2 () const | 
| Return the rotation acceleration as a quaternion. | |
| ChVector3< double > | GetAngVelLocal () const | 
| Compute the angular velocity (expressed in local coords). | |
| ChVector3< double > | GetAngVelParent () const | 
| Compute the actual angular velocity (expressed in parent coords). | |
| ChVector3< double > | GetAngAccLocal () const | 
| Compute the actual angular acceleration (expressed in local coords). | |
| ChVector3< double > | GetAngAccParent () const | 
| Compute the actual angular acceleration (expressed in parent coords). | |
| virtual void | SetCoordsysDt (const ChCoordsys< double > &csys_dt) | 
| Set both linear and rotation velocities as a single ChCoordsys derivative. | |
| virtual void | SetPosDt (const ChVector3< double > &vel) | 
| Set the linear velocity. | |
| virtual void | SetLinVel (const ChVector3< double > &vel) | 
| Set the linear velocity. | |
| virtual void | SetRotDt (const ChQuaternion< double > &q_dt) | 
| Set the rotation velocity as a quaternion derivative.  More... | |
| virtual void | SetAngVelLocal (const ChVector3< double > &w) | 
| Set the rotation velocity from the given angular velocity (expressed in local coordinates). | |
| virtual void | SetAngVelParent (const ChVector3< double > &w) | 
| Set the rotation velocity from given angular velocity (expressed in parent coordinates). | |
| virtual void | SetCoordsysDt2 (const ChCoordsys< double > &csys_dtdt) | 
| Set the linear and rotation accelerations as a single ChCoordsys derivative. | |
| virtual void | SetPosDt2 (const ChVector3< double > &acc) | 
| Set the linear acceleration. | |
| virtual void | SetLinAcc (const ChVector3< double > &acc) | 
| Set the linear acceleration. | |
| virtual void | SetRotDt2 (const ChQuaternion< double > &q_dtdt) | 
| Set the rotation acceleration as a quaternion derivative.  More... | |
| virtual void | SetAngAccLocal (const ChVector3< double > &a) | 
| Set the rotation acceleration from given angular acceleration (expressed in local coordinates).  More... | |
| virtual void | SetAngAccParent (const ChVector3< double > &a) | 
| Set the rotation acceleration from given angular acceleration (expressed in parent coordinates). | |
| void | ComputeRotMatDt (ChMatrix33< double > &R_dt) const | 
| Compute the time derivative of the rotation matrix. | |
| void | ComputeRotMatDt2 (ChMatrix33< double > &R_dtdt) | 
| Compute the second time derivative of the rotation matrix. | |
| ChMatrix33< double > | GetRotMatDt () | 
| Return the time derivative of the rotation matrix. | |
| ChMatrix33< double > | GetRotMatDt2 () | 
| Return the second time derivative of the rotation matrix. | |
| void | ConcatenatePreTransformation (const ChFrameMoving< double > &F) | 
| Apply a transformation (rotation and translation) represented by another frame.  More... | |
| void | ConcatenatePostTransformation (const ChFrameMoving< double > &F) | 
| Apply a transformation (rotation and translation) represented by another frame F in local coordinate.  More... | |
| ChVector3< double > | PointSpeedLocalToParent (const ChVector3< double > &localpos) const | 
| Return the velocity in the parent frame of a point fixed to this frame and expressed in local coordinates. | |
| ChVector3< double > | PointSpeedLocalToParent (const ChVector3< double > &localpos, const ChVector3< double > &localspeed) const | 
| Return the velocity in the parent frame of a moving point, given the point location and velocity expressed in local coordinates. | |
| ChVector3< double > | PointAccelerationLocalToParent (const ChVector3< double > &localpos) const | 
| Return the acceleration in the parent frame of a point fixed to this frame and expressed in local coordinates.  More... | |
| ChVector3< double > | PointAccelerationLocalToParent (const ChVector3< double > &localpos, const ChVector3< double > &localspeed, const ChVector3< double > &localacc) const | 
| Return the acceleration in the parent frame of a moving point, given the point location, velocity, and acceleration expressed in local coordinates. | |
| ChVector3< double > | PointSpeedParentToLocal (const ChVector3< double > &parentpos, const ChVector3< double > &parentspeed) const | 
| Return the velocity of a point expressed in this frame, given the point location and velocity in the parent frame. | |
| ChVector3< double > | PointAccelerationParentToLocal (const ChVector3< double > &parentpos, const ChVector3< double > &parentspeed, const ChVector3< double > &parentacc) const | 
| Return the acceleration of a point expressed in this frame, given the point location, velocity, and acceleration in the parent frame. | |
| ChFrameMoving< double > | TransformLocalToParent (const ChFrameMoving< double > &F) const | 
| Transform a moving frame from 'this' local coordinate system to parent frame coordinate system. | |
| ChFrameMoving< double > | TransformParentToLocal (const ChFrameMoving< double > &F) const | 
| Transform a moving frame from the parent coordinate system to 'this' local frame coordinate system. | |
| bool | Equals (const ChFrameMoving< double > &other) const | 
| Returns true if this transform is identical to the other transform. | |
| bool | Equals (const ChFrameMoving< double > &other, double tol) const | 
| Returns true if this transform is equal to the other transform, within a tolerance 'tol'. | |
| virtual void | Invert () override | 
| Invert in place.  More... | |
| ChFrameMoving< double > | GetInverse () const | 
| Return the inverse transform. | |
|  Public Member Functions inherited from chrono::ChFrame< double > | |
| ChFrame () | |
| Default constructor (identity frame). | |
| ChFrame (const ChVector3< double > &v, const ChQuaternion< double > &q=ChQuaternion< double >(1, 0, 0, 0)) | |
| Construct from position and rotation (as quaternion). | |
| ChFrame (const ChVector3< double > &v, const ChMatrix33< double > &R) | |
| Construct from pos and rotation (as a 3x3 matrix). | |
| ChFrame (const ChVector3< double > &v, const double angle, const ChVector3< double > &u) | |
| Construct from position mv and rotation of angle alpha around unit vector mu. | |
| ChFrame (const ChCoordsys< double > &C) | |
| Construct from a coordsys. | |
| ChFrame (const ChFrame< double > &other) | |
| Copy constructor, build from another frame. | |
| ChFrame< double > & | operator= (const ChFrame< double > &other) | 
| Assignment operator: copy from another frame. | |
| bool | operator== (const ChFrame< double > &other) const | 
| Returns true for identical frames. | |
| bool | operator!= (const ChFrame< double > &other) const | 
| Returns true for different frames. | |
| ChFrame< double > | operator* (const ChFrame< double > &F) const | 
| Transform another frame through this frame.  More... | |
| ChVector3< double > | operator* (const ChVector3< double > &v) const | 
| Transform a vector through this frame (express in parent frame).  More... | |
| ChFrame< double > | operator>> (const ChFrame< double > &F) const | 
| Transform another frame through this frame.  More... | |
| ChVector3< double > | operator/ (const ChVector3< double > &v) const | 
| Transform a vector through this frame (express from parent frame).  More... | |
| ChFrame< double > & | operator>>= (const ChFrame< double > &F) | 
| Transform this frame by pre-multiplication with another frame.  More... | |
| ChFrame< double > & | operator>>= (const ChVector3< double > &v) | 
| Transform this frame by pre-multiplication with a given vector (translate frame). | |
| ChFrame< double > & | operator>>= (const ChQuaternion< double > &q) | 
| Transform this frame by pre-multiplication with a given quaternion (rotate frame). | |
| ChFrame< double > & | operator>>= (const ChCoordsys< double > &C) | 
| Transform this frame by pre-multiplication with a given coordinate system. | |
| ChFrame< double > & | operator*= (const ChFrame< double > &F) | 
| Transform this frame by post-multiplication with another frame.  More... | |
| const ChCoordsys< double > & | GetCoordsys () const | 
| Return both current rotation and translation as a ChCoordsys object. | |
| const ChVector3< double > & | GetPos () const | 
| Return the current translation vector. | |
| const ChQuaternion< double > & | GetRot () const | 
| Return the current rotation quaternion. | |
| const ChMatrix33< double > & | GetRotMat () const | 
| Return the current 3x3 rotation matrix. | |
| ChVector3< double > | GetRotAxis () const | 
| Get axis of finite rotation, in parent space. | |
| double | GetRotAngle () const | 
| Get angle of rotation about axis of finite rotation. | |
| virtual void | SetCoordsys (const ChCoordsys< double > &C) | 
| Impose both translation and rotation as a single ChCoordsys.  More... | |
| virtual void | SetCoordsys (const ChVector3< double > &v, const ChQuaternion< double > &q) | 
| Impose both translation and rotation.  More... | |
| virtual void | SetRot (const ChQuaternion< double > &q) | 
| Impose the rotation as a quaternion.  More... | |
| virtual void | SetRot (const ChMatrix33< double > &R) | 
| Impose the rotation as a 3x3 matrix.  More... | |
| virtual void | SetPos (const ChVector3< double > &pos) | 
| Impose the translation vector. | |
| void | ConcatenatePreTransformation (const ChFrame< double > &F) | 
| Apply a transformation (rotation and translation) represented by another frame.  More... | |
| void | ConcatenatePostTransformation (const ChFrame< double > &F) | 
| Apply a transformation (rotation and translation) represented by another frame F in local coordinate.  More... | |
| void | Move (const ChVector3< double > &v) | 
| An easy way to move the frame by the amount specified by vector v, (assuming v expressed in parent coordinates) | |
| void | Move (const ChCoordsys< double > &C) | 
| Apply both translation and rotation, assuming both expressed in parent coordinates, as a vector for translation and quaternion for rotation,. | |
| ChVector3< double > | TransformPointLocalToParent (const ChVector3< double > &v) const | 
| Transform a point from the local frame coordinate system to the parent coordinate system. | |
| ChVector3< double > | TransformPointParentToLocal (const ChVector3< double > &v) const | 
| Transforms a point from the parent coordinate system to local frame coordinate system. | |
| ChVector3< double > | TransformDirectionLocalToParent (const ChVector3< double > &d) const | 
| Transform a direction from the parent frame coordinate system to 'this' local coordinate system. | |
| ChVector3< double > | TransformDirectionParentToLocal (const ChVector3< double > &d) const | 
| Transforms a direction from 'this' local coordinate system to parent frame coordinate system. | |
| ChWrench< double > | TransformWrenchLocalToParent (const ChWrench< double > &w) const | 
| Transform a wrench from the local coordinate system to the parent coordinate system. | |
| ChWrench< double > | TransformWrenchParentToLocal (const ChWrench< double > &w) const | 
| Transform a wrench from the parent coordinate system to the local coordinate system. | |
| ChFrame< double > | TransformLocalToParent (const ChFrame< double > &F) const | 
| Transform a frame from 'this' local coordinate system to parent frame coordinate system. | |
| ChFrame< double > | TransformParentToLocal (const ChFrame< double > &F) const | 
| Transform a frame from the parent coordinate system to 'this' local frame coordinate system. | |
| bool | Equals (const ChFrame< double > &other) const | 
| Returns true if this transform is identical to the other transform. | |
| bool | Equals (const ChFrame< double > &other, double tol) const | 
| Returns true if this transform is equal to the other transform, within a tolerance 'tol'. | |
| void | Normalize () | 
| Normalize the rotation, so that quaternion has unit length. | |
| virtual void | SetIdentity () | 
| Sets to no translation and no rotation. | |
| ChFrame< double > | GetInverse () const | 
| Return the inverse transform. | |
|  Public Member Functions inherited from chrono::ChContactable | |
| void | AddCollisionModel (std::shared_ptr< ChCollisionModel > model) | 
| Add the collision model. | |
| void | AddCollisionShape (std::shared_ptr< ChCollisionShape > shape, const ChFrame<> &frame=ChFrame<>()) | 
| Add a collision shape.  More... | |
| std::shared_ptr< ChCollisionModel > | GetCollisionModel () const | 
| Access the collision model. | |
| void | SetUserData (const std::shared_ptr< void > &data) | 
| Set user-data associated with this contactable. | |
| bool | HasData () const | 
| Check if this contactable has associated user-data. | |
| template<typename T > | |
| std::shared_ptr< T > | GetUserData () const | 
| Get the user-data using static cast to a known type. | |
| void | ArchiveOut (ChArchiveOut &archive_out) | 
| Method to allow serialization of transient data to archives. | |
| void | ArchiveIn (ChArchiveIn &archive_in) | 
| Method to allow deserialization of transient data from archives. | |
|  Public Member Functions inherited from chrono::ChLoadableUVW | |
| virtual bool | IsTetrahedronIntegrationNeeded () | 
| If true, use quadrature over u,v,w in [0..1] range as tetrahedron volumetric coords (with z=1-u-v-w) otherwise use default quadrature over u,v,w in [-1..+1] as box isoparametric coords. | |
| virtual bool | IsTrianglePrismIntegrationNeeded () | 
| If true, use quadrature over u,v in [0..1] range as triangle natural coords (with z=1-u-v), and use linear quadrature over w in [-1..+1], otherwise use default quadrature over u,v,w in [-1..+1] as box isoparametric coords. | |
| Static Public Member Functions | |
| static void * | ArchiveInConstructor (ChArchiveIn &archive_in) | 
| Serialization for non-default constructor classes. | |
| Additional Inherited Members | |
|  Public Types inherited from chrono::ChContactable | |
| enum | Type { Type::UNKNOWN, Type::ONE_1, Type::ONE_2, Type::ONE_3, Type::ONE_4, Type::ONE_5, Type::ONE_6, Type::TWO_33, Type::TWO_66, Type::THREE_333, Type::THREE_666 } | 
| Contactable type (based on number of variables objects and their DOFs).  More... | |
|  Protected Member Functions inherited from chrono::ChObj | |
| int | GenerateUniqueIdentifier () | 
|  Protected Attributes inherited from chrono::ChBody | |
| std::vector< std::shared_ptr< ChMarker > > | marklist | 
| list of markers | |
| std::vector< std::shared_ptr< ChForce > > | forcelist | 
| list of forces | |
| ChVector3d | gyro | 
| gyroscopic torque, i.e. Qm = Wvel x (XInertia*Wvel) | |
| ChVector3d | Xforce | 
| force acting on body, applied to COM (in absolute coords) | |
| ChVector3d | Xtorque | 
| torque acting on body (in body local coords) | |
| std::vector< WrenchAccumulator > | accumulators | 
| ChVariablesBodyOwnMass | variables | 
| interface to solver (store inertia and coordinates) | |
| float | max_speed | 
| limit on linear speed | |
| float | max_wvel | 
| limit on angular velocity | |
| float | sleep_time | 
| float | sleep_minspeed | 
| float | sleep_minwvel | 
| float | sleep_starttime | 
| unsigned int | index | 
| unique sequential body identifier, used for indexing (internal use only) | |
|  Protected Attributes inherited from chrono::ChPhysicsItem | |
| ChSystem * | system | 
| parent system | |
| unsigned int | offset_x | 
| offset in vector of state (position part) | |
| unsigned int | offset_w | 
| offset in vector of state (speed part) | |
| unsigned int | offset_L | 
| offset in vector of lagrangian multipliers | |
|  Protected Attributes inherited from chrono::ChObj | |
| double | ChTime | 
| object simulation time | |
| std::string | m_name | 
| object name | |
| int | m_identifier | 
| object unique identifier | |
| int | m_tag | 
| user-supplied tag | |
| std::shared_ptr< ChVisualModelInstance > | vis_model_instance | 
| instantiated visualization model | |
| std::vector< std::shared_ptr< ChCamera > > | cameras | 
| set of cameras | |
|  Protected Attributes inherited from chrono::ChFrameMoving< double > | |
| ChCoordsys< double > | m_csys_dt | 
| rotation and position velocity, as vector + quaternion | |
| ChCoordsys< double > | m_csys_dtdt | 
| rotation and position acceleration, as vector + quaternion | |
|  Protected Attributes inherited from chrono::ChFrame< double > | |
| ChCoordsys< double > | m_csys | 
| position and rotation, as vector + quaternion | |
| ChMatrix33< double > | m_rmat | 
| 3x3 orthogonal rotation matrix | |
|  Protected Attributes inherited from chrono::ChContactable | |
| std::shared_ptr< ChCollisionModel > | collision_model | 
| collision model for the contactable object | |
| std::vector< ChVariables * > | m_contactable_variables | 
| variables associated with the contactable object | |
| std::shared_ptr< void > | m_data | 
| arbitrary user-data | |
Constructor & Destructor Documentation
◆ ChBodyEasyConvexHull() [1/2]
| chrono::ChBodyEasyConvexHull::ChBodyEasyConvexHull | ( | std::vector< ChVector3d > & | points, | 
| double | density, | ||
| bool | create_visualization = true, | ||
| bool | create_collision = false, | ||
| std::shared_ptr< ChContactMaterial > | material = nullptr | ||
| ) | 
Create a rigid body with optional convex hull visualization and/or collision shape.
The convex hull is defined with a set of points, expressed in a local frame. Mass and inertia are set automatically depending on density. The convex hull vertices are translated so that the barycenter coincides with the center of mass.
- Parameters
- 
  points points of the convex hull density density of the body create_visualization create visualization asset create_collision enable collision material surface contact material 
◆ ChBodyEasyConvexHull() [2/2]
| chrono::ChBodyEasyConvexHull::ChBodyEasyConvexHull | ( | std::vector< ChVector3d > & | points, | 
| double | density, | ||
| std::shared_ptr< ChContactMaterial > | material | ||
| ) | 
Create a rigid body with a convex hull visualization and collision shape.
The convex hull is defined with a set of points, expressed in a local frame. Mass and inertia are set automatically depending on density. The convex hull vertices are translated so that the barycenter coincides with the center of mass.
- Parameters
- 
  points points of the convex hull density density of the body material surface contact material 
The documentation for this class was generated from the following files:
- /builds/uwsbel/chrono/src/chrono/physics/ChBodyEasy.h
- /builds/uwsbel/chrono/src/chrono/physics/ChBodyEasy.cpp
