Description

Main namespace for the Chrono package.

Namespaces

 AssemblyLevel
 Enumerations for assembly level.
 
 bt_utils
 Utilities for Bullet-based collision detection.
 
 cascade
 Namespace with classes for the CASCADE module.
 
 copter
 Namespace with classes for the Copter models.
 
 cosimul
 Namespace with classes for the cosimulation module.
 
 curiosity
 Namespace with classes for the Curiosity model.
 
 fea
 Namespace for FEA classes.
 
 fsi
 Namespace with classes for the FSI module.
 
 gpu
 Namespace with classes for the Gpu module.
 
 irrlicht
 Namespace with classes for the Irrlicht module.
 
 mc_utils
 Utilities for Chrono multicore collision detection.
 
 modal
 Namespace with classes for the modal module.
 
 opengl
 Namespace with classes for the OpenGL module.
 
 parsers
 Namespace with classes for the Parsers module.
 
 particlefactory
 Namespace for classes that generate flows of particles.
 
 postprocess
 Namespace with classes for the POSTPROCESS module.
 
 robosimian
 Namespace with classes for the RoboSimian model.
 
 ros
 Namespace for Chrono::ROS.
 
 sensor
 Namespace for Chrono::Sensor.
 
 synchrono
 Namespace for SynChrono.
 
 turtlebot
 Namespace with classes for the Turtlebot model.
 
 utils
 Chrono core utilities.
 
 vehicle
 Namespace with classes for the VEHICLE module.
 
 viper
 Namespace with classes for the Viper model.
 
 vsg3d
 Namespace with classes for the VSG module.
 

Classes

struct  AngleAxis
 Representation of a rotation as angle-axis. More...
 
struct  AngleSet
 Representation of an Euler/Cardan angle set. More...
 
class  cbtArcArcCollisionAlgorithm
 Custom override of the default Bullet algorithm for 2Darc-2Darc collision. More...
 
class  cbtArcSegmentCollisionAlgorithm
 Custom override of the default Bullet algorithm for 2Dsegment-2Darc collision. More...
 
class  cbtCapsuleBoxCollisionAlgorithm
 Custom override of the default Bullet algorithm for capsule-box collision. More...
 
class  cbtCEtriangleShapeCollisionAlgorithm
 Custom override of the default Bullet algorithm for triangle-triangle collision. More...
 
class  cbtCylshellBoxCollisionAlgorithm
 Custom override of the default Bullet algorithm for cylshell-box collision. More...
 
class  cbtSphereCylinderCollisionAlgorithm
 Custom override of the default Bullet algorithm for sphere-cylinder collision. More...
 
class  Ch3DOFContainer
 Base class for containers of elements with 3 degrees of freedom (fluid nodes, rigid particles). More...
 
struct  ChAABB
 Axis-aligned bounding box. More...
 
class  ChArchive
 Base class for archives with pointers to shared objects. More...
 
class  ChArchiveIn
 Base class for deserializing from archives. More...
 
class  ChArchiveInBinary
 Deserialization from binary stream. More...
 
class  ChArchiveInJSON
 This is a class for deserializing from JSON archives. More...
 
class  ChArchiveInXML
 This is a class for deserializing from XML archives. More...
 
class  ChArchiveOut
 Base class for serializing into archives. More...
 
class  ChArchiveOutBinary
 Serialization to binary stream. More...
 
class  ChArchiveOutJSON
 Serialize objects using JSON format. More...
 
class  ChArchiveOutXML
 Serialize objects using JSON format. More...
 
class  ChAssembly
 Class for assemblies of physical items. More...
 
class  ChAssemblyAnalysis
 Class for assembly analysis. More...
 
class  ChBasisToolsBSpline
 Tools for evaluating basis functions for B-splines, parametrized with parameter u (as lines) These bases are often called "N" in literature. More...
 
class  ChBasisToolsBSplineSurfaces
 Tools for evaluating basis functions for tensor-product surface B-splines, parametrized with parameters u,v (as lines) These bases are often called "R" in literature. More...
 
class  ChBasisToolsNurbs
 Tools for evaluating basis functions for NURBS, parametrized with parameter u (as lines) These bases are often called "R" in literature. More...
 
class  ChBasisToolsNurbsSurfaces
 Tools for evaluating basis functions for tensor-product surface NURBS, parametrized with parameter u,v (as lines) These bases are often called "R" in literature. More...
 
class  ChBezierCurve
 Definition of a piece-wise cubic Bezier approximation of a 3D curve. More...
 
class  ChBezierCurveTracker
 Definition of a tracker on a ChBezierCurve path. More...
 
class  ChBody
 Class for Rigid Bodies. More...
 
class  ChBodyAuxRef
 Class for Rigid Bodies with an auxiliary Reference Frame. More...
 
class  ChBodyEasyBox
 Create rigid bodies with a box shape. More...
 
class  ChBodyEasyClusterOfSpheres
 Create rigid bodies with a shape made of a cluster of spheres. More...
 
class  ChBodyEasyConvexHull
 Create rigid bodies with a convex hull shape. More...
 
class  ChBodyEasyConvexHullAuxRef
 Create rigid body with a convex hull shape, with a reference frame distinct from the centroidal frame. More...
 
class  ChBodyEasyCylinder
 Create rigid bodies with a cylinder shape. More...
 
class  ChBodyEasyEllipsoid
 Create rigid bodies with an ellipsoid shape. More...
 
class  ChBodyEasyMesh
 Create rigid bodies with a mesh shape, with a reference frame distinct from the centroidal frame. More...
 
class  ChBodyEasySphere
 Create rigid bodies with a spherical shape. More...
 
class  ChBodyFrame
 Class for objects that represent moving frames in space and contain state variables. More...
 
class  ChBox
 A box geometric object for collisions and visualization. More...
 
class  ChBroadphase
 Class for performing broad-phase collision detection. More...
 
class  ChCamera
 Class for defining a camera point of view with basic settings. More...
 
class  ChCapsule
 A capsule geometric object for collision and visualization. More...
 
class  ChCastingMap
 Stores type-casting functions between different type pairs, allowing to pick them at runtime from std::type_index or classname Converting pointers between different classes is usually possible by standard type casting, given that the source and destination class types are known at compile time. This class allows to typecast between class types that are known only at runtime. The requirement is that the typecasting function has to be prepared in advance (i.e. at compile time), when the types are still known. For each potential conversion an instance of ChCastingMap has to be declared, together with its typecasting function. This procedure is simplified by the macros CH_UPCASTING(FROM, TO) and CH_UPCASTING_SANITIZED(FROM, TO, UNIQUETAG) When the conversion should take place the following can be called: ConversionMap::Convert(std::string("source_classname"), std::string("destination_classname"), <void* to object>) More...
 
class  ChClassFactory
 A class factory. More...
 
class  ChClassRegistration
 Macro to create a ChDetect_ArchiveInConstructor. More...
 
class  ChClassRegistrationBase
 Base class for all registration data of classes whose objects can be created via a class factory. More...
 
class  ChCLI
 Wrapper for cxxopts. More...
 
class  ChCollisionData
 Global data for the custom Chrono multicore collision system. More...
 
class  ChCollisionInfo
 Class defining basic geometric information for collision pairs. More...
 
class  ChCollisionModel
 Class defining the geometric model for collision detection. More...
 
class  ChCollisionModelBullet
 Class defining the Bullet geometric model for collision detection. More...
 
class  ChCollisionModelMulticore
 Geometric model for the custom multicore Chrono collision system. More...
 
class  ChCollisionPair
 Class for storing information about a collision point. More...
 
class  ChCollisionShape
 Class defining a collision shape. More...
 
class  ChCollisionShapeArc2D
 Collision 2D arc shape. More...
 
class  ChCollisionShapeBarrel
 Collision barrel shape. More...
 
class  ChCollisionShapeBox
 Collision box shape. More...
 
class  ChCollisionShapeCapsule
 Collision capsule shape. More...
 
class  ChCollisionShapeCone
 Collision cone shape. More...
 
class  ChCollisionShapeConvexHull
 Collision convex hull shape. More...
 
class  ChCollisionShapeCylinder
 Collision cylinder shape. More...
 
class  ChCollisionShapeCylindricalShell
 Collision cylindrical shell shape. More...
 
class  ChCollisionShapeEllipsoid
 Collision ellipsoid shape. More...
 
class  ChCollisionShapeMeshTriangle
 Collision shape representing a triangle in a connected mesh. More...
 
class  ChCollisionShapePath2D
 Collision 2D path shape. More...
 
class  ChCollisionShapePoint
 Collision point shape. More...
 
class  ChCollisionShapeRoundedBox
 Collision rounded-box shape. More...
 
class  ChCollisionShapeRoundedCylinder
 Collision rounded-cylinder shape. More...
 
class  ChCollisionShapeSegment2D
 Collision 2D segment shape. More...
 
class  ChCollisionShapeSphere
 Collision sphere shape. More...
 
class  ChCollisionShapeTriangle
 Collision triangle shape. More...
 
class  ChCollisionShapeTriangleMesh
 Collision mesh shape. More...
 
class  ChCollisionSystem
 Base class for generic collision engine. More...
 
class  ChCollisionSystemBullet
 Collision engine based on the Bullet library. More...
 
class  ChCollisionSystemChronoMulticore
 Chrono custom multicore collision system. More...
 
class  ChCollisionSystemMulticore
 Chrono multicore collision system. More...
 
class  ChColor
 Definition of a visual color. More...
 
class  ChCone
 A conical geometric object for collisions and visualization. More...
 
class  ChConstantDistribution
 Class for a distribution with a single 'value' that has probability 1.0. More...
 
class  ChConstraint
 Base class for representing constraints (bilateral or unilateral). More...
 
class  ChConstraintBilateral
 Bilateral (joint) constraints. More...
 
class  ChConstraintNgeneric
 Constraint between N objects of type ChVariables(). More...
 
class  ChConstraintRigidRigid
 Unilateral (contact) constraints. More...
 
class  ChConstraintThree
 This class is inherited by the base ChConstraint(), which does almost nothing. More...
 
class  ChConstraintThreeBBShaft
 Constraint between two bodies (2x6dof in space) and a 1D dof (a shaft). More...
 
class  ChConstraintThreeGeneric
 Constraint between three objects of type ChVariables(), with generic number of scalar variables each. More...
 
class  ChConstraintTuple_1vars
 This is a container for 'half' of a constraint, and contains a tuple of 1 or 2 or 3 differently-sized jacobian chunks. More...
 
class  ChConstraintTuple_2vars
 Case of tuple with reference to 2 ChVariable objects: More...
 
class  ChConstraintTuple_3vars
 Case of tuple with reference to 3 ChVariable objects: More...
 
class  ChConstraintTuple_4vars
 Case of tuple with reference to 4 ChVariable objects: More...
 
class  ChConstraintTwo
 This class implements the functionality for a constraint between a COUPLE of TWO objects of type ChVariables(), and defines two constraint matrices, whose column number automatically matches the number of elements in variables vectors. More...
 
class  ChConstraintTwoBodies
 Constraint between two objects of type ChVariablesBody. More...
 
class  ChConstraintTwoGeneric
 This class implements the functionality for a constraint between a COUPLE of TWO objects of type ChVariables(), with generic number of scalar variables each (ex.ChVariablesGeneric() or ChVariablesBody() ) and defines two constraint matrices, whose column number automatically matches the number of elements in variables vectors. More...
 
class  ChConstraintTwoGenericBoxed
 This class is inherited from the base ChConstraintTwoGeneric, which can be used for most pairwise constraints, and adds the feature that the multiplier must be l_min < l < l_max that is, the multiplier is 'boxed'. More...
 
class  ChConstraintTwoTuples
 This constraint is built on top of two ChConstraintTuple objects, each with a tuple of 1 or 2 or 3 differently-sized jacobian chunks. More...
 
class  ChConstraintTwoTuplesContactN
 Normal reaction between two objects, each represented by a tuple of ChVariables objects. More...
 
class  ChConstraintTwoTuplesFrictionT
 Base class for friction constraints between two objects, each represented by a tuple of ChVariables objects. More...
 
class  ChConstraintTwoTuplesFrictionTall
 This is enough to use dynamic_casting<> to detect all template types from ChConstraintTwoTuplesFrictionT. More...
 
class  ChConstraintTwoTuplesRollingN
 Normal reaction between two objects, each represented by a tuple of ChVariables objects. More...
 
class  ChConstraintTwoTuplesRollingNall
 This is enough to use dynamic_casting<> to detect all template types from ChConstraintTwoTuplesRollingN. More...
 
class  ChConstraintTwoTuplesRollingT
 Base class for friction constraints between two objects, each represented by a tuple of ChVariables objects. More...
 
class  ChConstraintTwoTuplesRollingTall
 This is enough to use dynamic_casting<> to detect all template types from ChConstraintTwoTuplesRollingT. More...
 
class  ChContactable
 Interface for objects that generate contacts. More...
 
class  ChContactContainer
 Class representing a container of many contacts. More...
 
class  ChContactContainerMulticore
 Class representing a container of many contacts, implemented as a linked list of contact tuples. More...
 
class  ChContactContainerMulticoreNSC
 Specialization of the multicore contact container for NSC contacts. More...
 
class  ChContactContainerMulticoreSMC
 Specialization of the multicore contact container for SMC contacts. More...
 
class  ChContactContainerNSC
 Class representing a container of many non-smooth contacts. More...
 
class  ChContactContainerSMC
 Class representing a container of many smooth (penalty) contacts. More...
 
class  ChContactMaterial
 Base class for specifying material properties for contact force generation. More...
 
class  ChContactMaterialComposite
 Base class for composite material for a contact pair. More...
 
class  ChContactMaterialCompositeNSC
 Composite NSC material data for a contact pair. More...
 
class  ChContactMaterialCompositeSMC
 Composite SMC material data for a contact pair. More...
 
class  ChContactMaterialCompositionStrategy
 Base class for material composition strategy. More...
 
class  ChContactMaterialData
 Material information for a collision shape. More...
 
class  ChContactMaterialNSC
 Material data for a collision surface for use with non-smooth (complementarity) contact method. More...
 
class  ChContactMaterialSMC
 Material data for a collision surface for use with smooth (penalty) contact method. More...
 
class  ChContactNSC
 Class for non-smooth contact between two generic ChContactable objects. More...
 
class  ChContactNSCrolling
 Class for non-smooth contact between two generic ChContactable objects. More...
 
class  ChContactSMC
 Class for smooth (penalty-based) contact between two generic contactable objects. More...
 
class  ChContactTuple
 Base class for contact between two generic ChContactable objects. More...
 
class  ChContinuumDistribution
 Class that can be used to generate sample numbers according to a probability distribution. More...
 
class  ChConvexDecomposition
 Base interface class for convex decomposition. More...
 
class  ChConvexDecompositionHACD
 Class for wrapping the HACD convex decomposition code by Khaled Mamou. More...
 
class  ChConvexDecompositionHACDv2
 Class for wrapping the HACD convex decomposition code revisited by John Ratcliff. More...
 
class  ChConveyor
 Class for conveyor belt. More...
 
class  ChCoordsys
 Representation of a transform with translation and rotation. More...
 
class  ChCubicSpline
 Implementation of 1-D piece-wise cubic spline curves. More...
 
class  ChCylinder
 A cylindrical geometric object for collisions and visualization. More...
 
class  ChDefaultContactForceTorqueSMC
 Default implementation of the SMC normal and tangential force calculation. More...
 
class  ChDirectSolverLS
 Base class for sparse direct linear solvers. More...
 
class  ChDirectSolverLScomplex
 Base class for sparse direct linear solvers with complex coefficients. More...
 
class  ChDiscreteDistribution
 Class that can be used to generate sample numbers according to a discrete probability distribution. More...
 
class  ChDistribution
 Base class for all random distributions. More...
 
class  ChEllipsoid
 An ellipsoid geometric object for collisions and such. More...
 
class  ChEnumMapperBase
 Class for mapping enums to ChNameValue pairs that contain a 'readable' ascii string of the selected enum. More...
 
class  ChExplicitTimestepper
 Base properties for explicit solvers. More...
 
class  ChExternalDynamics
 Physics element that carries its own dynamics, described as a system of ODEs. More...
 
class  ChFeeder
 Class for feeders like vibrating bowls, conveyor belts. More...
 
class  ChFluidContainer
 Container of fluid particles. More...
 
class  ChFmMatrix34
 Special MBD 3x4 matrix [Fm(q)], as in [Fp(q)] * [Fm(q)]' = [A(q)]. More...
 
class  ChForce
 Forces are objects which must be attached to rigid bodies in order to apply torque or force to such body. More...
 
class  ChFpMatrix34
 Special MBD 3x4 matrix [Fp(q)], as in [Fp(q)] * [Fm(q)]' = [A(q)]. More...
 
class  ChFrame
 Representation of a 3D transform. More...
 
class  ChFrameMoving
 Representation of a moving 3D. More...
 
class  ChFseqNode
 Node for the list of functions in a ChFunctionSequence object. More...
 
class  ChFunction
 Interface base class for scalar functions. More...
 
class  ChFunctionBSpline
 B-Spline motion function. More...
 
class  ChFunctionConst
 Function returnin a constant value. More...
 
class  ChFunctionConstAcc
 Constant acceleration function. More...
 
class  ChFunctionConstJerk
 Ramp function composed by seven segments with constant jerk. More...
 
class  ChFunctionCycloidal
 Cycloidal step function. More...
 
class  ChFunctionDerivative
 Derivative of a function. More...
 
class  ChFunctionFillet3
 Cubic fillet function. More...
 
class  ChFunctionIntegral
 Integral of a function. More...
 
class  ChFunctionInterp
 Interpolation function: More...
 
class  ChFunctionLambda
 Lambda function wrapper Allows the usage of C++ lambda functions as ChFunction objects. More...
 
class  ChFunctionMirror
 Mirror function. More...
 
class  ChFunctionOperator
 Operation between functions: More...
 
class  ChFunctionPoly
 Polynomial function. More...
 
class  ChFunctionPoly23
 Cubic smooth step. More...
 
class  ChFunctionPoly345
 Polynomial step function y = h * (10*(x/w)^3 - 15*(x/w)^4 + 6*(x/w)^5) where: More...
 
class  ChFunctionPosition
 Interface base class for scalar->vector functions. More...
 
class  ChFunctionPositionLine
 A motion function p=f(s) where p(t) is defined with a ChLine geometry object, ex. More...
 
class  ChFunctionPositionSetpoint
 A motion function p=f(s) where p(t) is an externally-provided sample, as a ZERO_ORDER_HOLD (zero order hold) of FIRST_ORDER_HOLD (first order). More...
 
class  ChFunctionPositionXYZFunctions
 A motion function p=f(s) where p(t) is defined with three independent ChFunction objects, each for px, py, pz component. More...
 
class  ChFunctionRamp
 Ramp function. More...
 
class  ChFunctionRepeat
 Repeat function: y = __/__/__/ More...
 
class  ChFunctionRotation
 Interface base class for scalar->quaternion functions of the type: More...
 
class  ChFunctionRotationABCFunctions
 A rotation function q=f(s) where q(s) is defined with three ChFunction objects, each per an an angle in an intrinsic triplets of angles (e.g. More...
 
class  ChFunctionRotationAxis
 A rotation function q=f(s) where q(s) is defined with axis V and angle alpha, assuming fixed axis of rotation V and a angle of rotation alpha about that axis, expressed with a ChFunction object alpha=alpha(s). More...
 
class  ChFunctionRotationBSpline
 A rotation function q=f(s) that interpolates n rotations using a "quaternion B-Spline" of generic order. More...
 
class  ChFunctionRotationSetpoint
 A rotation q=f(s) provided from a rotation sample, continuously updated by the user, behaving as a ZERO_ORDER_HOLD (zero order hold) of FIRST_ORDER_HOLD (first order). More...
 
class  ChFunctionRotationSQUAD
 A rotation function q=f(s) that interpolates n rotations using a SQUAD spherical quadrangle interpolation between quaternions. More...
 
class  ChFunctionSequence
 Sequence function: y = sequence_of_functions(f1(y), f2(y), f3(y)) All other function types can be inserted into this. More...
 
class  ChFunctionSetpoint
 Function that returns Y from an externally-provided value, as a ZERO_ORDER_HOLD (zero order hold) block. More...
 
class  ChFunctionSetpointCallback
 Interface for functions that uses a callback to return a Y value, as a ZERO_ORDER_HOLD (zero order hold) block. More...
 
class  ChFunctionSine
 Sine function y = A*sin(2*PI*f + phase)`. More...
 
class  ChFunctionSineStep
 Sinusoidal ramp between two (x,y) points p1 and p2. More...
 
class  ChFunctorArchiveIn
 Functor to call the ArchiveIn function for unrelated classes that implemented them. More...
 
class  ChGeometry
 Base class for geometric objects used for collisions and visualization. More...
 
class  ChGlMatrix34
 Special MBD 3x4 matrix [Gl(q)], as in local angular speed conversion. More...
 
class  ChGlyphs
 Class for referencing a set of 'glyphs', that are simple symbols such as arrows or points to be drawn for showing vector directions etc. More...
 
class  ChGwMatrix34
 Special MBD 3x4 matrix [Gw(q)], as in absolute angular speed conversion. More...
 
class  ChHydraulicActuator2
 Hydraulic actuator using a circuit with 2 volumes. More...
 
class  ChHydraulicActuator3
 Hydraulic actuator using a circuit with 3 volumes. More...
 
class  ChHydraulicActuatorBase
 Base class for a hydraulic actuator. More...
 
class  ChHydraulicCylinder
 ChHydraulicCylinder - a simple hydraulic cylinder Schematic: More...
 
class  ChHydraulicDirectionalValve4x3
 ChHydraulicDirectionalValve4x3 - a computational model of 4/3 directional valve Schematic: More...
 
class  ChHydraulicThrottleValve
 ChHydraulicThrottleValve - a semi-empirical model of a throttle valve Schematic: More...
 
class  ChImplicitIterativeTimestepper
 Base properties for implicit solvers. More...
 
class  ChImplicitTimestepper
 Base class for implicit solvers (double inheritance) More...
 
class  ChIndexedNodes
 Interface class for clusters of points that can be accessed with an index. More...
 
class  ChIndexedParticles
 Interface class for clusters of particles that can be accessed with an index. More...
 
class  ChInertiaUtils
 Class with some static functions that can be used to make computations with inertia tensors. More...
 
class  ChIntegrable
 Interface class for all objects that support time integration. More...
 
class  ChIntegrableIIorder
 Special subcase: II-order differential system. More...
 
class  ChIntegrand1D
 Base class for 1D integrand T = f(x) to be used in ChQuadrature. More...
 
class  ChIntegrand2D
 Base class for 2D integrand T = f(x,y) to be used in ChQuadrature. More...
 
class  ChIntegrand3D
 Base class for 3D integrand T = f(x,y,z) to be used in ChQuadrature. More...
 
class  ChIterativeSolver
 Base class for iterative solvers. More...
 
class  ChIterativeSolverLS
 Base class for Chrono solvers based on Eigen iterative linear solvers. More...
 
class  ChIterativeSolverMulticore
 Base class for all iterative solvers. More...
 
class  ChIterativeSolverMulticoreNSC
 Wrapper class for all complementarity solvers. More...
 
class  ChIterativeSolverMulticoreSMC
 Iterative solver for SMC (penalty-based) problems. More...
 
class  ChIterativeSolverVI
 Base class for iterative solvers aimed at solving complementarity problems arising from QP optimization problems. More...
 
class  ChKRMBlock
 Sparse blocks loaded into the KRM global matrix, associated with a set of variables. More...
 
class  ChLine
 Base class for all geometric objects representing lines in 3D space. More...
 
class  ChLineArc
 Geometric object representing an arc or a circle in 3D space. More...
 
class  ChLineBezier
 Geometric object representing a piecewise cubic Bezier curve in 3D. More...
 
class  ChLineBSpline
 Geometric object representing a Bspline spline. More...
 
class  ChLineCam
 Geometric object describing the profile of a cam. More...
 
class  ChLineNurbs
 Geometric object representing a NURBS spline. More...
 
class  ChLinePath
 Geometric object representing an sequence of other ChLine objects, The ChLine objects are assumed to be properly concatenated and to have C0 continuity. More...
 
class  ChLinePoly
 Geometric object representing a polygonal line in 3D space, controlled by control points. More...
 
class  ChLineSegment
 Geometric object representing a segment in 3D space with two end points. More...
 
class  ChLink
 Base class for joints between two ChBodyFrame objects. More...
 
class  ChLinkBase
 Base class for all types of constraints in the 3D space. More...
 
class  ChLinkBushing
 Link with up to 6-degree-of-freedom linear compliance between rigid bodies. More...
 
class  ChLinkDistance
 Fixed distance constraint between two points on two ChBodyFrame objects. More...
 
class  ChLinkForce
 Class for forces in link joints of type ChLinkLock. More...
 
class  ChLinkLimit
 Class for limits in ChLinkLock joints. More...
 
class  ChLinkLock
 Base class for joints implemented using the "lock" formulation. More...
 
class  ChLinkLockAlign
 Align joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockBrake
 Link representing a brake between two rigid bodies, including the sticking effect. More...
 
class  ChLinkLockClearance
 A class for the custom fast simulation of revolute joints with clearance. More...
 
class  ChLinkLockCylindrical
 Cylindrical joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockFree
 Free joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockGear
 Gear link between two rigid bodies. More...
 
class  ChLinkLockLinActuator
 Linear actuator between two markers on two rigid bodies The distance between the two markers changes in time following a user-provided function. More...
 
class  ChLinkLockLock
 6-dof locked joint, with the link-lock formulation. More...
 
class  ChLinkLockOldham
 Oldham joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockParallel
 Parallel joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPerpend
 Perpendicularity joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPlanar
 Plane-plane joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPointLine
 Point-line joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPointPlane
 Point-plane joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPointSpline
 ChLinkLockPointSpline class. More...
 
class  ChLinkLockPrismatic
 Prismatic joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockPulley
 Class to create pulleys on two rigid bodies, connected by a belt. More...
 
class  ChLinkLockRevolute
 Revolute joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockRevolutePrismatic
 RevolutePrismatic joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockScrew
 Screw joint between two rigid bodies. More...
 
class  ChLinkLockSpherical
 Spherical joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockTrajectory
 ChLinkLockTrajectory class. More...
 
class  ChLinkMarkers
 Class for links which connect two 'markers'. More...
 
class  ChLinkMask
 Mask structure for N scalar constraint equations between two bodies. More...
 
class  ChLinkMaskLF
 Specialized ChLinkMask class, for constraint equations of the ChLinkLock link. More...
 
class  ChLinkMate
 Base class for constraints between two frames attached to two bodies. More...
 
class  ChLinkMateCylindrical
 Mate constraint of coaxial type. More...
 
class  ChLinkMateDistanceZ
 Mate constraining distance of origin of frame 2 respect to Z axis of frame 1. More...
 
class  ChLinkMateFix
 Mate constraint to completely fix relative motion of two frames. More...
 
class  ChLinkMateGeneric
 Generic mate constraint. More...
 
class  ChLinkMateOrthogonal
 Mate constraint of orthogonal type. More...
 
class  ChLinkMateParallel
 Mate constraint of parallel type. More...
 
class  ChLinkMatePlanar
 Mate constraint of plane-to-plane type. More...
 
class  ChLinkMatePrismatic
 Mate constraint of prismatic type. More...
 
class  ChLinkMateRackPinion
 Rack-pinion link between two body frames. More...
 
class  ChLinkMateRevolute
 Mate constraint of revolute type. More...
 
class  ChLinkMateSpherical
 Mate constraint of spherical type. More...
 
class  ChLinkMotionImposed
 A joint to enforce position and rotation between two frames on two bodies, using six rheonomic constraints. More...
 
class  ChLinkMotor
 Base class for all "motor" constraints between two frames on two bodies. More...
 
class  ChLinkMotorLinear
 Base class for all linear "motor" constraints between two frames on two bodies. More...
 
class  ChLinkMotorLinearDriveline
 Couples the relative translation of two bodies (along Z direction of the link frames) with the rotation of a 1D shaft. More...
 
class  ChLinkMotorLinearForce
 A linear motor that applies a force between two frames on two bodies along Z axis. More...
 
class  ChLinkMotorLinearPosition
 A linear motor that enforces the position z(t) between two frames on two bodies, using a rheonomic constraint. More...
 
class  ChLinkMotorLinearSpeed
 A linear motor that enforces the speed v(t) between two frames on two bodies, using a rheonomic constraint. More...
 
class  ChLinkMotorRotation
 Base class for all rotational "motor" constraints between two frames on two bodies. More...
 
class  ChLinkMotorRotationAngle
 A motor that enforces the rotation angle r(t) between two frames on two bodies, using a rheonomic constraint. More...
 
class  ChLinkMotorRotationDriveline
 Couple for the relative rotation of two bodies (along the link frame Z direction) with the rotation of a 1D shaft. More...
 
class  ChLinkMotorRotationSpeed
 A motor that enforces the angular speed w(t) between two frames on two bodies, using a rheonomic constraint. More...
 
class  ChLinkMotorRotationTorque
 A motor that applies a torque between two frames on two bodies. More...
 
class  ChLinkRevolute
 Class for modeling a revolute joint between two two ChBodyFrame objects. More...
 
class  ChLinkRevoluteSpherical
 Composite revolute-spherical joint between two two bodies. More...
 
class  ChLinkRevoluteTranslational
 Class for modeling a composite revolute-translational joint between two ChBodyFrame objects. More...
 
class  ChLinkRSDA
 Class for rotational spring-damper-actuator (RSDA) with the torque specified through a functor object. More...
 
class  ChLinkTSDA
 Class for translational spring-damper-actuator (TSDA) with the force optionally specified through a functor object. More...
 
class  ChLinkUniversal
 Class for modeling a universal joint between two two ChBodyFrame objects. More...
 
class  ChLoad
 Load acting on a single ChLoadable item, via ChLoader objects. More...
 
class  ChLoadable
 Interface for objects that can be subject to loads (forces) Forces can be distributed on UV surfaces, or lines, etc.,so look also the more detailed children classes. More...
 
class  ChLoadableU
 Interface for objects that can be subject to line loads, distributed along U coordinate of the object. More...
 
class  ChLoadableUV
 Interface for objects that can be subject to area loads, distributed along UV coordinates of the object. More...
 
class  ChLoadableUVW
 Interface for objects that can be subject to volume loads, distributed along UVW coordinates of the object. More...
 
class  ChLoadBase
 Base class for loads. More...
 
class  ChLoadBodyBody
 Base class for wrench loads (a force + a torque) acting between two bodies. More...
 
class  ChLoadBodyBodyBushingGeneric
 Load for a visco-elastic translational/rotational bushing acting between two bodies. More...
 
class  ChLoadBodyBodyBushingMate
 Load for a visco-elastic translational/rotational bushing acting between two bodies. More...
 
class  ChLoadBodyBodyBushingPlastic
 Load for a visco-elasto-plastic bushing acting between two bodies. More...
 
class  ChLoadBodyBodyBushingSpherical
 Load for a visco-elastic bushing acting between two bodies. More...
 
class  ChLoadBodyBodyTorque
 Load representing a torque applied between two bodies. More...
 
class  ChLoadBodyForce
 Load representing a concentrated force acting on a rigid body. More...
 
class  ChLoadBodyInertia
 Load for adding mass and inertia to a body. More...
 
class  ChLoadBodyMesh
 Loads applied to a triangle mesh associated with a ChBody, as a cluster of forces operating on the rigid body. More...
 
class  ChLoadBodyTorque
 Load representing a torque applied to a rigid body. More...
 
class  ChLoadContainer
 A container of ChLoad objects. More...
 
class  ChLoadCustom
 Loads acting on a single ChLoadable item. More...
 
class  ChLoadCustomMultiple
 Loads acting on multiple ChLoadable items. More...
 
class  ChLoader
 Loads applied to a single ChLoadable object. More...
 
class  ChLoaderForceOnSurface
 Simple surface loader: a constant force vector, applied to a point on a u,v surface. More...
 
class  ChLoaderGravity
 Commonly used volume loader: constant gravitational load. More...
 
class  ChLoaderNodeXYZ
 Loader for a constant force applied at a XYZ node. More...
 
class  ChLoaderPressure
 Commonly used surface loader: constant pressure load, a 3D per-area force aligned with the surface normal. More...
 
class  ChLoaderU
 Loaders for ChLoadableU objects (which support line loads). More...
 
class  ChLoaderUatomic
 Loader for ChLoadableU objects (which support line loads), for concentrated loads. More...
 
class  ChLoaderUdistributed
 Loader for ChLoadableU objects (which support line loads), for loads of distributed type. More...
 
class  ChLoaderUV
 Loaders for ChLoadableUV objects (which support surface loads). More...
 
class  ChLoaderUVatomic
 Loaders for ChLoadableUV objects (which support surface loads), for concentrated loads. More...
 
class  ChLoaderUVdistributed
 Loaders for ChLoadableUV objects (which support surface loads), for loads of distributed type. More...
 
class  ChLoaderUVW
 Loaders for ChLoadableUVW objects (which support volume loads). More...
 
class  ChLoaderUVWatomic
 Loaders for ChLoadableUVW objects (which support volume loads), for concentrated loads. More...
 
class  ChLoaderUVWdistributed
 Loaders for ChLoadableUVW objects (which support volume loads), for loads of distributed type. More...
 
class  ChLoadJacobians
 Utility class for storing Jacobian matrices. More...
 
class  ChLoadNodeXYZ
 Force at XYZ node (ready to use load). More...
 
class  ChLoadNodeXYZBody
 Base class for loads representing a concentrated force acting between a ChNodeXYZ and a ChBody Users should inherit from this and implement a custom ComputeForce(). More...
 
class  ChLoadNodeXYZBodyBushing
 Load representing a XYZ bushing between a ChNodeXYZ and a ChBody application point, with given with spring stiffness as a ChFunction of displacement, for each X,Y,Z direction along the auxiliary frame at the attachment point. More...
 
class  ChLoadNodeXYZBodySpring
 Load representing a spring between a ChNodeXYZ and a ChBody. More...
 
class  ChLoadNodeXYZForce
 Base class for loads representing a concentrated force acting on a ChNodeXYZ. More...
 
class  ChLoadNodeXYZForceAbs
 Load representing a concentrated force acting on a ChNodeXYZ. More...
 
class  ChLoadNodeXYZNodeXYZ
 Base class for loads representing a concentrated force acting between two ChNodeXYZ. More...
 
class  ChLoadNodeXYZNodeXYZBushing
 Load representing an XYZ bushing between two ChNodeXYZ. More...
 
class  ChLoadNodeXYZNodeXYZSpring
 Load representing a spring between two ChNodeXYZ. More...
 
class  ChLumpingParms
 Helper class for lumping parameters. More...
 
class  ChMarker
 Markers are auxiliary reference frames attached to a rigid body and moving with the body. More...
 
class  ChMatlabEngine
 Class for accessing the Matlab engine with a C++ wrapper. More...
 
class  ChMatrix33
 Definition of a 3x3 fixed-size matrix to represent 3D rotations and inertia tensors. More...
 
class  ChMulticoreDataManager
 Global data manager for Chrono::Multicore. More...
 
class  ChMumpsEngine
 Wrapper class for the MUMPS direct linear solver. More...
 
class  ChNameValue
 Class to manage name-value pairs for serialization/deserialization. More...
 
class  ChNarrowphase
 Class for performing narrowphase collision detection. More...
 
class  ChNodeBase
 Class for a node, that has some degrees of freedom. More...
 
class  ChNodeXYZ
 Class for a single 'point' node, that has 3 DOF degrees of freedom and a mass. More...
 
class  ChNonlinearSolver
 Solver for systems of nonlinear equations. More...
 
class  ChNormalDistribution
 Class that generates the Gauss Normal distribution (the 'bell' distribution). More...
 
class  ChObj
 Base class for all Chrono objects. More...
 
class  ChObjectExplorer
 A helper class to provide some basic mechanism of C++ reflection (introspection). More...
 
class  ChOMP
 Dummy no-op functions in case that no parallel multithreading via OpenMP is available. More...
 
class  CHOMPmutex
 Dummy no-op mutex in case that no parallel multithreading via OpenMP is available. More...
 
struct  CHOMPscopedLock
 Exception-safe wrapper to a mutex: it automatically locks the mutex as soon as the wrapper is created, and releases the mutex when the wrapper is deleted (you simply put the wrapper in a code section delimited by {} parentheses, so it is deleted by the compiler when exiting the scope of the section or in case of premature exit because of an exception throw) More...
 
class  ChOutputASCII
 Output objects structure to a human-readable ASCII format. More...
 
class  ChOutputFMU
 Class for serializing variables to FmuComponentBase. More...
 
class  ChParticle
 Class for a single particle clone in the ChParticleCloud cluster. More...
 
class  ChParticleBase
 Base class for a single particle to be used in ChIndexedParticles containers. More...
 
class  ChParticleCloud
 Class for clusters of 'clone' particles, that is many rigid objects with the same shape and mass. More...
 
class  ChParticleContainer
 Container of rigid particles (3 DOF). More...
 
class  ChPhysicsItem
 Base class for physics items that are part of a simulation. More...
 
class  ChProjectConstraints
 Functor class for performing projection on the hyper-cone. More...
 
class  ChProjectNone
 Functor class for performing a single cone projection. More...
 
class  ChProperty
 Base class for properties to attach to vertices or particles as arrays of data. More...
 
class  ChPropertyColor
 Data is an array of colors. More...
 
class  ChPropertyQuaternion
 Data is an array of quaternions (for rotations) More...
 
class  ChPropertyScalar
 Data is an array of floats. More...
 
class  ChPropertyT
 Templated property: a generic array of items of type T. More...
 
class  ChPropertyVector
 Data is an array of vectors. More...
 
class  ChProximityContainer
 Class representing the interface for containers of proximity pairs, that is pairs of collision models that have been obtained from the broadphase collision. More...
 
class  ChQuadrature
 Gauss-Legendre quadrature in 1D, 2D, or 3D. More...
 
class  ChQuadratureTables
 Polynomial roots and weights for the Gauss-Legendre quadrature. More...
 
class  ChQuadratureTablesTetrahedron
 Polynomial roots and weights for quadrature over a tetrahedron. More...
 
class  ChQuadratureTablesTriangle
 Polynomial roots and weights for quadrature over a triangle. More...
 
class  ChQuaternion
 Class defining quaternion objects, that is four-dimensional numbers. More...
 
class  ChRayTest
 Class for performing ray intersection tests. More...
 
class  ChRealtimeStepTimer
 Class for a timer which attempts to enforce soft real-time. More...
 
class  ChRoundedBox
 A rounded box (sphere-swept box) geometric object for collisions and visualization. More...
 
class  ChRoundedCylinder
 A rounded cylinder (sphere-swept cylinder) geometric object for collision and visualization. More...
 
class  ChSchurProduct
 Functor class for calculating the Schur product of the matrix of unilateral constraints. More...
 
class  ChSchurProductBilateral
 Functor class for performing the Schur product of the matrix of bilateral constraints. More...
 
class  ChShaft
 Class for one-degree-of-freedom mechanical parts with associated inertia (mass or moment of rotational inertia). More...
 
class  ChShaftBodyRotation
 Constraint between a 3D ChBody object and a ChShaft object that represents a 1D rotational DOF. More...
 
class  ChShaftBodyTranslation
 Constraint between a 3D ChBody object and a ChShaft object that represents a 1D translational DOF. More...
 
class  ChShaftsAppliedTorque
 Class for defining a user-defined torque between two one-degree-of-freedom parts. More...
 
class  ChShaftsClutch
 Class for defining a clutch or a brake (1D model) between two one-degree-of-freedom parts. More...
 
class  ChShaftsCouple
 Base class for defining constraints between a couple of two one-degree-of-freedom parts. More...
 
class  ChShaftsElasticGear
 Elastic gear coupling between two shafts. More...
 
class  ChShaftsFreewheel
 Class for defining a 'freewheel' (a 1D model of a ratchet wheel) between two one-degree-of-freedom parts. More...
 
class  ChShaftsGear
 Class for defining a 'transmission ratio' (a 1D gear) between two one-degree-of-freedom parts. More...
 
class  ChShaftsGearbox
 Class for defining a gearbox. More...
 
class  ChShaftsGearboxAngled
 Class for defining a gearbox with 1D input and 1D output, but with different directions in 3D space. More...
 
class  ChShaftsLoad
 Base class for defining loads between a couple of two one-degree-of-freedom parts. More...
 
class  ChShaftsMotor
 Base class for all motors between two 1D elements of ChShaft class. More...
 
class  ChShaftsMotorLoad
 Motor to apply a load between two shafts. More...
 
class  ChShaftsMotorPosition
 Motor to enforce the relative position r(t) between two shafts, using a rheonomic constraint. More...
 
class  ChShaftsMotorSpeed
 Motor to enforce the relative speed w(t) between two shafts, using a rheonomic constraint. More...
 
class  ChShaftsPlanetary
 Class for defining a planetary gear between three one-degree-of-freedom parts. More...
 
class  ChShaftsThermalEngine
 Class for defining a thermal engine between two one-degree-of-freedom parts/ The first shaft is the 'crankshaft' to whom the torque is applied, the second is the motor block, that receives the negative torque. More...
 
class  ChShaftsTorque
 Base class for all classes defining a torque between two one-degree-of-freedom parts. More...
 
class  ChShaftsTorqueConverter
 Class for defining a torque converter between two one-degree-of-freedom parts. More...
 
class  ChShaftsTorsionSpring
 Class for defining a torsional spring-damper between two 1D parts. More...
 
class  ChShaftsTorsionSpringDamper
 Class for defining a torsional spring-damper between two 1D parts. More...
 
class  ChSharedMassBody
 Reference to a single mass property shared by multiple ChVariablesBodySharedMass objects. More...
 
class  ChSolver
 Base class for all Chrono solvers (for linear problems or complementarity problems). More...
 
class  ChSolverADMM
 An iterative solver based on modified version of ADMM Alternating Direction Method of Multipliers. More...
 
class  ChSolverAPGD
 An iterative solver based on Nesterov's Projected Gradient Descent. More...
 
class  ChSolverBB
 An iterative solver based on modified Krylov iteration of spectral projected gradients with Barzilai-Borwein. More...
 
class  ChSolverBiCGSTAB
 BiCGSTAB iterative solver. More...
 
class  ChSolverComplexPardisoMKL
 Sparse complex Pardiso direct solver.
. More...
 
class  ChSolverGMRES
 GMRES iterative solver. More...
 
class  ChSolverLS
 Base class for solvers aimed at solving linear systems. More...
 
class  ChSolverMatlab
 Class for using a Matlab linear solver from Chrono programs. More...
 
class  ChSolverMINRES
 MINRES iterative solver. More...
 
class  ChSolverMulticore
 Base class for all Chrono::Multicore solvers. More...
 
class  ChSolverMulticoreAPGD
 Accelerated Projected Gradient Descent (APGD) solver. More...
 
class  ChSolverMulticoreAPGDREF
 Accelerated Projected Gradient Descent (APGD) solver. Reference implementation. More...
 
class  ChSolverMulticoreBB
 Barzilai-Borwein solver. More...
 
class  ChSolverMulticoreCG
 Conjugate gradient solver. More...
 
class  ChSolverMulticoreGS
 Gauss Seidel solver. More...
 
class  ChSolverMulticoreJacobi
 Jacobi solver. More...
 
class  ChSolverMulticoreMinRes
 MINRES solver. More...
 
class  ChSolverMulticoreSPGQP
 Spectral Projected Gradient solver. More...
 
class  ChSolverMumps
 Interface to the MUMPS parallel sparse direct solver. More...
 
class  ChSolverPardisoMKL
 Interface to the Intel MKL Pardiso parallel sparse direct solver. More...
 
class  ChSolverPJacobi
 An iterative solver for VI based on projective fixed point method (projected Jacobi). More...
 
class  ChSolverPMINRES
 An iterative solver based on modified Krylov iteration of MINRES type with gradient projections (similar to nonlinear CG with Polyak-Ribiere). More...
 
class  ChSolverPSOR
 An iterative solver based on projective fixed point method, with overrelaxation and immediate variable update as in SOR methods. More...
 
class  ChSolverPSSOR
 An iterative solver based on symmetric projective fixed point method, with overrelaxation and immediate variable update as in SSOR methods. More...
 
class  ChSolverSparseComplexLU
 Sparse complex LU direct solver. More...
 
class  ChSolverSparseComplexQR
 Sparse complex QR direct solver. More...
 
class  ChSolverSparseLU
 Sparse LU direct solver. More...
 
class  ChSolverSparseQR
 Sparse QR direct solver. More...
 
class  ChSolverVI
 Base class for solvers aimed at solving complementarity problems arising from QP optimization problems. More...
 
class  ChSparsityPatternLearner
 Utility class for extracting sparsity patter from a sparse matrix. More...
 
class  ChSphere
 A spherical geometric object for collisions and visualization. More...
 
class  ChStarMatrix33
 Special MBD 3x3 "star" matrix, , representing vector cross products. More...
 
class  ChStarMatrix44
 Special MBD 4x4 "star" matrix, representing quaternion cross product. More...
 
class  ChState
 Class for state of time-integrable objects. More...
 
class  ChStateDelta
 Class for incremental form of state of time-integrable objects. More...
 
class  ChStaticAnalysis
 Base class for static analysis. More...
 
class  ChStaticLinearAnalysis
 Linear static analysis. More...
 
class  ChStaticNonLinearAnalysis
 Nonlinear static analysis. More...
 
class  ChStaticNonLinearIncremental
 Nonlinear static analysis where the user can define external load(s) that will be incremented gradually during the solution process. More...
 
class  ChStaticNonLinearRheonomicAnalysis
 Nonlinear static analysis for a mechanism that is rotating/moving in steady state. More...
 
class  ChStaticNonLinearRigidMotion
 Nonlinear static analysis for the system including rigid motion DOFs, for instance, a single pendulum. More...
 
class  ChStrainTensor
 Class for strain tensors, in compact Voight notation that is with 6 components in a column. More...
 
class  ChStressTensor
 Class for stress tensors, in compact Voight notation that is with 6 components in a column. More...
 
class  ChSurface
 Base class for all geometric objects representing bi-parametric surfaces in 3D space. More...
 
class  ChSurfaceNurbs
 Geometric object representing a NURBS surface. More...
 
class  ChSystem
 Chrono Simulation System. More...
 
class  ChSystemDescriptor
 Base class for collecting objects inherited from ChConstraint, ChVariables and optionally ChKRMBlock. More...
 
class  ChSystemDescriptorMulticore
 System descriptor for Chrono::Multicore. More...
 
class  ChSystemMulticore
 Base class for Chrono::Multicore systems. More...
 
class  ChSystemMulticoreNSC
 Multicore system using non-smooth contact (complementarity-based) method. More...
 
class  ChSystemMulticoreSMC
 Multicore system using smooth contact (penalty-based) method. More...
 
class  ChSystemNSC
 Class for a physical system in which contact is modeled using a non-smooth (complementarity-based) method. More...
 
class  ChSystemSMC
 Class for a physical system in which contact is modeled using a smooth (penalty-based) method. More...
 
class  ChTexture
 Class for defining a texture. More...
 
class  ChTimer
 Chrono wrappers for the high-resolution timer. More...
 
class  ChTimerMulticore
 Utility class for managing a collection of timer objects. More...
 
class  ChTimestepper
 Base class for timesteppers, i.e., time integrators that can advance a system state. More...
 
class  ChTimestepperEulerExpl
 Euler explicit timestepper. More...
 
class  ChTimestepperEulerExplIIorder
 Euler explicit timestepper customized for II order. More...
 
class  ChTimestepperEulerImplicit
 Performs a step of Euler implicit for II order systems. More...
 
class  ChTimestepperEulerImplicitLinearized
 Performs a step of Euler implicit for II order systems using the Anitescu/Stewart/Trinkle single-iteration method, that is a bit like an implicit Euler where one performs only the first Newton corrector iteration. More...
 
class  ChTimestepperEulerImplicitProjected
 Performs a step of Euler implicit for II order systems using a semi implicit Euler without constraint stabilization, followed by a projection. More...
 
class  ChTimestepperEulerSemiImplicit
 Euler semi-implicit timestepper. More...
 
class  ChTimestepperHeun
 Performs a step of a Heun explicit integrator. It is like a 2nd Runge Kutta. More...
 
class  ChTimestepperHHT
 Implementation of the HHT implicit integrator for II order systems. More...
 
class  ChTimestepperIIorder
 Base class for 2nd order timesteppers, i.e., a time integrator for a ChIntegrableIIorder. More...
 
class  ChTimestepperIorder
 Base class for 1st order timesteppers, that is a time integrator for a ChIntegrable. More...
 
class  ChTimestepperLeapfrog
 Performs a step of a Leapfrog explicit integrator. More...
 
class  ChTimestepperNewmark
 Performs a step of Newmark constrained implicit for II order DAE systems. More...
 
class  ChTimestepperRungeKuttaExpl
 Performs a step of a 4th order explicit Runge-Kutta integration scheme. More...
 
class  ChTimestepperTrapezoidal
 Performs a step of trapezoidal implicit for II order systems. More...
 
class  ChTimestepperTrapezoidalLinearized
 Performs a step of trapezoidal implicit linearized for II order systems. More...
 
class  ChTimestepperTrapezoidalLinearized2
 Performs a step of trapezoidal implicit linearized for II order systems. More...
 
class  ChTriangle
 A triangle geometric shape for collisions and visualization. More...
 
class  ChTriangleMesh
 Base class for triangle meshes. More...
 
class  ChTriangleMeshConnected
 A triangle mesh with connectivity info: vertices can be shared between faces. More...
 
class  ChTriangleMeshSoup
 A basic triangle mesh: just a list of triangles (no edge connectivity info). More...
 
class  ChUniformDistribution
 Class for a distribution with uniform probability between a lower 'min' value and upper 'max' value. More...
 
class  ChValue
 Class to handle C++ values of generic type using type erasure and functors. More...
 
class  ChVariables
 Base class for representing objects that introduce 'variables' and their associated mass submatrices. More...
 
class  ChVariablesBody
 Specialized class for representing a 6-DOF 3D rigid body, with mass matrix and associated variables. More...
 
class  ChVariablesBodyOwnMass
 Specialized class for representing a 6-DOF 3D rigid body, with mass matrix and associated variables. More...
 
class  ChVariablesBodySharedMass
 Specialized class for representing a 6-DOF 3D rigid body, with mass matrix and associated variables. More...
 
class  ChVariablesGeneric
 Specialized class for representing a N-DOF item for a system, that is an item with mass matrix and associate variables. More...
 
class  ChVariablesGenericDiagonalMass
 Specialized class for representing a N-DOF item for a system, that is an item with a diagonal mass matrix and associated variables. More...
 
class  ChVariablesNode
 Specialized class for representing a 3-DOF item for a system, that is a 3D point node, with mass matrix and associate variables (a 3 element vector, ex.speed) More...
 
class  ChVariablesShaft
 Specialized class for representing a 1-DOF item for a system, that is a shaft, with inertia and associated variable (rotational speed) More...
 
class  ChVariableTupleCarrier_1vars
 This is a set of 'helper' classes that make easier to manage the templated structure of the tuple constraints. More...
 
class  ChVector2
 Definition of a general purpose 2d vector. More...
 
class  ChVector3
 Definition of general purpose 3d vector variables, such as points in 3D. More...
 
class  ChVisualMaterial
 Definition of a visual material. More...
 
class  ChVisualModel
 Base class for a visual model which encapsulates a set of visual shapes. More...
 
class  ChVisualModelInstance
 A visual model instance encodes a potentially shared visual model and its owning physics item. More...
 
class  ChVisualShape
 Base class for a visualization asset for rendering (run-time or post processing). More...
 
class  ChVisualShapeBarrel
 Class for referencing a barrel shape (a lathed arc) that can be visualized in some way. More...
 
class  ChVisualShapeBox
 Class for a box shape that can be visualized in some way. More...
 
class  ChVisualShapeCapsule
 Class for referencing a capsule shape that can be visualized in some way. More...
 
class  ChVisualShapeCone
 Class for referencing a cone shape that can be visualized in some way. More...
 
class  ChVisualShapeCylinder
 Class for referencing a cylinder shape that can be visualized in some way. More...
 
class  ChVisualShapeEllipsoid
 Class for referencing an ellipsoid shape that can be visualized in some way. More...
 
class  ChVisualShapeFEA
 FEA mesh visualization. More...
 
class  ChVisualShapeLine
 Class for referencing a ChLine that can be visualized in some way. More...
 
class  ChVisualShapeModelFile
 Class for referencing a Wavefront OBJ file containing a shape that can be visualized in some way. More...
 
class  ChVisualShapePath
 Class for referencing a ChLinePath that can be visualized in some way. More...
 
class  ChVisualShapePointPoint
 Base class for visualization of some deformable line shape between two moving points related to the parent ChPhysicsItem. More...
 
class  ChVisualShapeRotSpring
 Shape representing a rotational spring. More...
 
class  ChVisualShapeRoundedBox
 Class for referencing a rounded box shape that can be visualized in some way. More...
 
class  ChVisualShapeRoundedCylinder
 Class for referencing a rounded cylinder shape that can be visualized in some way. More...
 
class  ChVisualShapeSegment
 Shape for visualizing a line segment between two moving points related to the parent ChPhysicsItem. More...
 
class  ChVisualShapeSphere
 A spherical geometric object for collisions and visualization. More...
 
class  ChVisualShapeSpring
 Shape for visualizing a coil spring between two moving points related to the parent ChPhysicsItem. More...
 
class  ChVisualShapeSurface
 Class for referencing a ChSurface u,v, parametric surface that can be visualized in some way. More...
 
class  ChVisualShapeTriangleMesh
 Class for referencing a triangle mesh shape that can be visualized in some way. More...
 
class  ChVisualSystem
 Base class for a Chrono run-time visualization system. More...
 
class  ChVoightTensor
 Base class for stress and strain tensors, in compact Voight notation. More...
 
class  ChVolume
 Base class for all geometric objects representing tri-parametric surfaces in 3D space. More...
 
class  ChWeibullDistribution
 Class that generates a Weibull distribution. More...
 
struct  ChWrench
 Definition of a wrench (force + torque). More...
 
class  ChZhangDistribution
 Class that generates the Zhang distribution, a modified exponential distribution. More...
 
class  collision_measures
 Collision_measures. More...
 
class  collision_settings
 Chrono::Multicore collision_settings. More...
 
class  ConvexBase
 Base class for convex contact shapes. More...
 
class  ConvexShape
 Convex contact shape. More...
 
class  ConvexShapeCustom
 Custom contact shape. More...
 
class  ConvexShapeSphere
 Sphere contact shape. More...
 
class  ConvexShapeTetrahedron
 Tetrahedron contact shape. More...
 
class  ConvexShapeTriangle
 Triangle contact shape. More...
 
class  FmuChronoComponentBase
 Extension of FmuComponentBase class for Chrono FMUs. More...
 
class  FmuChronoUnit
 Extension of FmuUnit class for Chrono FMUs. More...
 
class  HeightColorCallback
 Predefined particle cloud dynamic coloring based on particle height. More...
 
struct  host_container
 Structure of arrays containing simulation data. More...
 
class  measures_container
 Aggregate of collision and solver measures. More...
 
struct  MPM_Settings
 Settings for the Material Point Method. More...
 
class  quaternion
 Chrono multicore quaternion class. More...
 
class  real2
 Chrono::Multicore pair (2-dimensional vector). More...
 
class  real3
 Chrono::Multicore triplet (3-dimensional vector). More...
 
class  real4
 Chrono multicore qudruple (4-dimensional array). More...
 
class  settings_container
 Aggregate of all settings for Chrono::Multicore. More...
 
struct  shape_container
 Structure of arrays containing rigid collision shape information. More...
 
class  solver_measures
 Solver measures. More...
 
class  solver_settings
 Chrono::Multicore solver_settings. More...
 
struct  state_container
 Structure of arrays containing state data. More...
 
struct  TimerData
 Wrapper class for a timer object. More...
 

Typedefs

typedef std::shared_ptr< ChVisualMaterialChVisualMaterialSharedPtr
 
typedef thrust::pair< real3, real3bbox
 
typedef int shape_type
 Readibility type definition.
 
typedef ChCoordsys< double > ChCoordsysd
 Alias for double-precision coordinate systems. More...
 
typedef ChCoordsys< float > ChCoordsysf
 Alias for single-precision coordinate systems. More...
 
typedef ChFrame< double > ChFramed
 Alias for double-precision coordinate frames. More...
 
typedef ChFrame< float > ChFramef
 Alias for double-precision coordinate frames. More...
 
template<typename T = double>
using ChMatrixDynamic = Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
 Dense matrix with dynamic size (i.e., with unknown at compile time) and row-major storage. More...
 
template<typename T , int M, int N>
using ChMatrixNM = Eigen::Matrix< T, M, N, Eigen::RowMajor >
 Dense matrix with fixed size (known at compile time) and row-major storage. More...
 
template<typename T = double>
using ChMatrixDynamic_col = Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor >
 Dense matrix with dynamic size (i.e., with unknown at compile time) and column-major storage. More...
 
template<typename T , int M, int N>
using ChMatrixNM_col = Eigen::Matrix< T, M, N, Eigen::ColMajor >
 Dense matrix with fixed size (known at compile time) and column-major storage. More...
 
template<typename T >
using ChMatrix66 = ChMatrixNM< T, 6, 6 >
 Alias for a 6x6 matrix templated by coefficient type (row-major storage).
 
using ChMatrix66d = ChMatrix66< double >
 Alias for a 6x6 matrix of doubles.
 
using ChMatrix66f = ChMatrix66< float >
 Alias for a 6x6 matrix of floats.
 
template<typename T = double>
using ChVectorDynamic = Eigen::Matrix< T, Eigen::Dynamic, 1, Eigen::ColMajor >
 Column vector with dynamic size (i.e., with size unknown at compile time). More...
 
template<typename T = double>
using ChRowVectorDynamic = Eigen::Matrix< T, 1, Eigen::Dynamic, Eigen::RowMajor >
 Row vector with dynamic size (i.e., with size unknown at compile time). More...
 
template<typename T , int N>
using ChVectorN = Eigen::Matrix< T, N, 1 >
 Column vector with fixed size (known at compile time). More...
 
template<typename T , int N>
using ChRowVectorN = Eigen::Matrix< T, 1, N, Eigen::RowMajor >
 Row vector with fixed size (known at compile time). More...
 
template<typename T = double>
using ChArray = Eigen::Array< T, Eigen::Dynamic, 1, Eigen::ColMajor >
 General-purpose column array with dynamic size. More...
 
template<typename T , int N>
using ChArrayN = Eigen::Array< T, N, 1 >
 Column array with fixed size (known at compile time). More...
 
using ChMatrixRef = Eigen::Ref< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > >
 Reference to a dense matrix expression, with double coefficients. More...
 
using ChMatrixConstRef = const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > > &
 Constant reference to a dense matrix expression, with double coefficients. More...
 
using ChVectorRef = Eigen::Ref< Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor > >
 Reference to a column vector expression, with double coefficients. More...
 
using ChVectorConstRef = const Eigen::Ref< const Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor > > &
 Constant reference to a column vector expression, with double coefficients. More...
 
using ChRowVectorRef = Eigen::Ref< Eigen::Matrix< double, 1, Eigen::Dynamic, Eigen::RowMajor > >
 Reference to a row vector expression, with double coefficients. More...
 
using ChRowVectorConstRef = const Eigen::Ref< const Eigen::Matrix< double, 1, Eigen::Dynamic, Eigen::RowMajor > > &
 Constant reference to a row vector expression, with double coefficients. More...
 
template<typename T = double>
using ChArrayRef = Eigen::Ref< Eigen::Array< T, Eigen::Dynamic, Eigen::ColMajor > > &
 Reference to an array expression, templated by coefficient type. More...
 
template<typename T = double>
using ChArrayConstRef = const Eigen::Ref< const Eigen::Array< T, Eigen::Dynamic, 1, Eigen::ColMajor > > &
 Constant reference to an array expression, templated by coefficient type. More...
 
using ChSparseMatrix = Eigen::SparseMatrix< double, Eigen::RowMajor, int >
 Sparse matrix representation. More...
 
using ChMatrix33d = ChMatrix33< double >
 Alias for a 3x3 matrix of doubles.
 
using ChMatrix33f = ChMatrix33< float >
 Alias for a 3x3 matrix of floats.
 
template<typename T = double>
using ChMatrix34 = Eigen::Matrix< T, 3, 4, Eigen::RowMajor >
 3x4 dense matrix (fixed-size, row-major ordering)
 
template<typename T = double>
using ChMatrix43 = Eigen::Matrix< T, 4, 3, Eigen::ColMajor >
 4x3 dense matrix (fixed-size, row-major ordering)
 
template<typename T = double>
using ChMatrix44 = Eigen::Matrix< T, 4, 4, Eigen::RowMajor >
 4x4 dense matrix (fixed-size, row-major ordering)
 
typedef ChQuaternion< double > ChQuaterniond
 Alias for double-precision quaternions. More...
 
typedef ChQuaternion< float > ChQuaternionf
 Alias for single-precision quaternions. More...
 
typedef ChVector2< double > ChVector2d
 Alias for double-precision vectors. More...
 
typedef ChVector2< float > ChVector2f
 Alias for single-precision vectors. More...
 
typedef ChVector2< int > ChVector2i
 Alias for integer vectors. More...
 
typedef ChVector2< bool > ChVector2b
 Alias for bool vectors. More...
 
typedef ChVector3< double > ChVector3d
 Alias for double-precision vectors. More...
 
typedef ChVector3< float > ChVector3f
 Alias for single-precision vectors. More...
 
typedef ChVector3< int > ChVector3i
 Alias for integer vectors. More...
 
typedef ChVector3< bool > ChVector3b
 Alias for bool vectors. More...
 
typedef ChWrench< double > ChWrenchd
 Alias for double-precision wrenches.
 
typedef ChWrench< float > ChWrenchf
 Alias for single-precision wrenches.
 
typedef double real
 
typedef std::shared_ptr< ChContactMaterialChContactMaterialSharedPtr
 
typedef ChVectorN< double, 2 > Vec2
 
typedef ChVectorN< double, 3 > Vec3
 

Enumerations

enum  CameraVerticalDir { Y, Z }
 Vertical direction.
 
enum  RotRepresentation {
  RotRepresentation::ANGLE_AXIS, RotRepresentation::ROTATION_VECTOR, RotRepresentation::EULER_ANGLES_ZXZ, RotRepresentation::CARDAN_ANGLES_ZXY,
  RotRepresentation::CARDAN_ANGLES_ZYX, RotRepresentation::CARDAN_ANGLES_XYZ, RotRepresentation::RODRIGUES
}
 Definitions of various rotation representations for conversions. More...
 
enum  ChAxis { ChAxis::X, ChAxis::Y, ChAxis::Z }
 Enumeration for the 3 frame directions. More...
 
enum  ChContactMethod { ChContactMethod::NSC, ChContactMethod::SMC }
 Enumeration of contact methods. More...
 
enum  ChCausalityType {
  parameter, calculatedParameter, input, output,
  local, independent
}
 
enum  ChVariabilityType {
  constant, fixed, tunable, discrete,
  continuous
}
 
enum  SolverType {
  SolverType::STEEPEST_DESCENT, SolverType::GRADIENT_DESCENT, SolverType::CONJUGATE_GRADIENT, SolverType::CONJUGATE_GRADIENT_SQUARED,
  SolverType::BICONJUGATE_GRADIENT, SolverType::BICONJUGATE_GRADIENT_STAB, SolverType::MINIMUM_RESIDUAL, SolverType::QUASI_MINIMUM_RESIDUAL,
  SolverType::APGD, SolverType::APGDREF, SolverType::JACOBI, SolverType::GAUSS_SEIDEL,
  SolverType::PDIP, SolverType::BB, SolverType::SPGQP
}
 Iterative solver type. More...
 
enum  SolverMode { SolverMode::NORMAL, SolverMode::SLIDING, SolverMode::SPINNING, SolverMode::BILATERAL }
 Enumeration for solver mode. More...
 
enum  SystemType { SystemType::SYSTEM_NSC, SystemType::SYSTEM_SMC }
 Enumeration for system type. More...
 
enum  BilateralType {
  BODY_BODY, SHAFT_SHAFT, SHAFT_SHAFT_SHAFT, SHAFT_BODY,
  SHAFT_SHAFT_BODY, UNKNOWN
}
 Enumeration for bilateral constraint types. More...
 
enum  LoggingLevel {
  LoggingLevel::LOG_NONE, LoggingLevel::LOG_INFO, LoggingLevel::LOG_TRACE, LoggingLevel::LOG_WARNING,
  LoggingLevel::LOG_ERROR
}
 Supported Logging Levels. More...
 

Functions

ChVector3fFetchOrAllocate (std::vector< ChVector3f > &mvector, unsigned int &id)
 
void TriangleNormalsReset (std::vector< ChVector3d > &normals, std::vector< int > &accumul)
 
void TriangleNormalsCompute (ChVector3i norm_indexes, ChVector3i vert_indexes, std::vector< ChVector3d > &vertexes, std::vector< ChVector3d > &normals, std::vector< int > &accumul)
 
void TriangleNormalsSmooth (std::vector< ChVector3d > &normals, std::vector< int > &accumul)
 
int addContactPoint (const cbtVector3 &pc, int iface, const cbtVector3 &hdims, const cbtTransform &X_box, cbtManifoldResult *resultOut)
 
int addContactPoint (const cbtVector3 &p, const cbtVector3 &c, const cbtVector3 &a, const cbtScalar h, const cbtScalar r, const cbtTransform &X_box, cbtManifoldResult *resultOut)
 
int GetIndex (ChVector3d vertex, std::vector< ChVector3d > &vertexOUT, double tol)
 
void FuseMesh (std::vector< ChVector3d > &vertexIN, std::vector< ChVector3i > &triangleIN, std::vector< ChVector3d > &vertexOUT, std::vector< ChVector3i > &triangleOUT, double tol=0.0)
 
void TransformToCOG (ChBody *body, const ChVector3d &pos, const ChMatrix33<> &rot, ChFrame<> &frame)
 
void DrawHemisphere (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, double radius, const ChColor &color)
 
void DrawSphere (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, double radius, const ChColor &color)
 
void DrawBox (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, const ChVector3d &hdim, const ChColor &color)
 
void DrawCylinder (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, double radius, double hlen, const ChColor &color)
 
void DrawCone (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, double radius, double hlen, const ChColor &color)
 
void DrawCapsule (ChCollisionSystem::VisualizationCallback *vis, const ChCoordsys<> &csys, double radius, double hlen, const ChColor &color)
 
int GridCoord (real x, real inv_bin_edge, real minimum)
 
int GridHash (int x, int y, int z, const vec3 &bins_per_axis)
 
real3 GetCenter (const ConvexBase *Shape)
 
void FindCenter (const ConvexBase *shapeA, const ConvexBase *shapeB, simplex &portal)
 
void MPRSupport (const ConvexBase *shapeA, const ConvexBase *shapeB, const real3 &n, const real &envelope, support &s)
 
void ExpandPortal (simplex &portal)
 
real3 PortalDir (const simplex &portal)
 
void FindPos (const simplex &portal, real3 &point)
 
int portalEncapsulesOrigin (const simplex &portal, const real3 &n)
 
int portalCanEncapsuleOrigin (const simplex &portal, const real3 &n)
 
int portalReachTolerance (const simplex &portal, const real3 &n)
 
real Vec3Dist2 (const real3 a, const real3 b)
 
real Vec3PointSegmentDist2 (const real3 &P, const real3 &x0, const real3 &b, real3 &witness)
 
real Vec3PointSegmentDist2 (const real3 &P, const real3 &x0, const real3 &b)
 
real Vec3PointTriDist2 (const real3 &P, const real3 &x0, const real3 &B, const real3 &C, real3 &witness)
 
real Vec3PointTriDist2 (const real3 &P, const real3 &V0, const real3 &V1, const real3 &V2)
 
void FindPenetration (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, simplex &portal, real &depth, real3 &n, real3 &point)
 
void FindPenetrationTouch (const ConvexBase *shapeA, const ConvexBase *shapeB, simplex &portal, real &depth, real3 &n, real3 &point)
 
void FindPenetrationSegment (const ConvexBase *shapeA, const ConvexBase *shapeB, simplex &portal, real &depth, real3 &n, real3 &point)
 
bool FindPortal (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, simplex &portal, real3 &n)
 
int DiscoverPortal (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, simplex &portal)
 
int RefinePortal (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, simplex &portal)
 
bool MPRContact (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, real3 &returnNormal, real3 &point, real &depth)
 
void MPRGetPoints (const ConvexBase *shapeA, const ConvexBase *shapeB, const real &envelope, real3 &N, real3 p0, real3 &p1, real3 &p2)
 
bool sphere_sphere (const real3 &pos1, const real &radius1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool capsule_sphere (const real3 &pos1, const quaternion &rot1, const real &radius1, const real &hlen1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool cylinder_sphere (const real3 &pos1, const quaternion &rot1, const real &radius1, const real &hlen1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool roundedcyl_sphere (const real3 &pos1, const quaternion &rot1, const real &radius1, const real &hlen1, const real &srad1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool box_sphere (const real3 &pos1, const quaternion &rot1, const real3 &hdims1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool roundedbox_sphere (const real3 &pos1, const quaternion &rot1, const real3 &hdims1, const real &srad1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
bool triangle_sphere (const real3 &A1, const real3 &B1, const real3 &C1, const real3 &pos2, const real &radius2, const real &separation, real3 &norm, real &depth, real3 &pt1, real3 &pt2, real &eff_radius)
 
int capsule_capsule (const real3 &pos1, const quaternion &rot1, const real &radius1, const real &hlen1, const real3 &pos2, const quaternion &rot2, const real &radius2, const real &hlen2, const real &separation, real3 *norm, real *depth, real3 *pt1, real3 *pt2, real *eff_radius)
 
int box_capsule (const real3 &pos1, const quaternion &rot1, const real3 &hdims1, const real3 &pos2, const quaternion &rot2, const real &radius2, const real &hlen2, const real &separation, real3 *norm, real *depth, real3 *pt1, real3 *pt2, real *eff_radius)
 
int box_cylshell (const real3 &pos1, const quaternion &rot1, const real3 &hdims, const real3 &pos2, const quaternion &rot2, const real &radius, const real &hlen, const real &separation, real3 *norm, real *depth, real3 *pt1, real3 *pt2, real *eff_radius)
 
int box_box (const real3 &posT, const quaternion &rotT, const real3 &hdimsT, const real3 &posO, const quaternion &rotO, const real3 &hdimsO, const real &separation, real3 *norm, real *depth, real3 *ptT, real3 *ptO, real *eff_radius)
 
int triangle_box (const real3 &pos1, const quaternion &rot1, const real3 &hdims1, const real3 *v2, const real &separation, real3 *norm, real *depth, real3 *pt1, real3 *pt2, real *eff_radius)
 
bool sphere_ray (const real3 &pos, const real &radius, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool aabb_ray (const real3 &hdims, const real3 &start, const real3 &end, real &t, real3 &loc, real3 &normal)
 
bool box_ray (const real3 &pos, const quaternion &rot, const real3 &hdims, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool cylsurf_ray (const real &radius, const real &hlen, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool hemisphere_ray (int cap, const real &radius, const real &hlen, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool disk_ray (int cap, const real &radius, const real &hlen, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool capsule_ray (const real3 &pos, const quaternion &rot, const real &radius, const real &hlen, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool cylinder_ray (const real3 &pos, const quaternion &rot, const real &radius, const real &hlen, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
bool triangle_ray (const real3 &A, const real3 &B, const real3 &C, const real3 &start, const real3 &end, real3 &normal, real &mindist2)
 
void * aligned_malloc (size_t size, size_t alignment)
 
void aligned_free (void *ptr)
 
template<typename T , typename std::enable_if<!std::is_polymorphic< T >::value >::type * = nullptr>
void * getVoidPointer (T *ptr)
 Type-erase pointer-to-object after making sure that it is pointing to the proper address Casting to void* through a static_cast leads to different results: More...
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChCoordsys< Real > &cs)
 Insertion of coordsys to output stream.
 
template<class Real >
ChVector3< Real > operator* (const ChCoordsys< Real > &Fa, const ChVector3< Real > &Fb)
 The '*' operator that transforms 'mixed' types: vector_C = frame_A * vector_B; where frame_A is a ChCoordsys vector_B is a ChVector Returns a ChVector. More...
 
template<class Real >
ChCoordsys< Real > operator* (const ChVector3< Real > &Fa, const ChCoordsys< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChCoordsys Returns a ChCoordsys. More...
 
template<class Real >
ChVector3< Real > operator>> (const ChVector3< Real > &Fa, const ChCoordsys< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: vector_C = vector_A >> frame_B; where vector_A is a ChVector frame_B is a ChCoordsys Returns a ChVector. More...
 
template<class Real >
ChCoordsys< Real > operator>> (const ChCoordsys< Real > &Fa, const ChVector3< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChCoordsys vector_B is a ChVector Returns a ChCoordsys. More...
 
template<class Real >
ChQuaternion< Real > operator* (const ChCoordsys< Real > &Fa, const ChQuaternion< Real > &Fb)
 The '*' operator that transforms 'mixed' types: quat_C = frame_A * quat_B; where frame_A is a ChCoordsys quat_B is a ChQuaternion Returns a ChQuaternion. More...
 
template<class Real >
ChCoordsys< Real > operator* (const ChQuaternion< Real > &Fa, const ChCoordsys< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChCoordsys Returns a ChCoordsys. More...
 
template<class Real >
ChQuaternion< Real > operator>> (const ChQuaternion< Real > &Fa, const ChCoordsys< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: quat_C = quat_A >> frame_B; where quat_A is a ChQuaternion frame_B is a ChCoordsys Returns a ChQuaternion. More...
 
template<class Real >
ChCoordsys< Real > operator>> (const ChCoordsys< Real > &Fa, const ChQuaternion< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChCoordsys frame_B is a ChQuaternion Returns a ChCoordsys. More...
 
template<class Real >
ChCoordsys< Real > operator* (const ChFrame< Real > &Fa, const ChCoordsys< Real > &Cb)
 The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrame frame_B is a ChCoordsys Returns a ChCoordsys. More...
 
template<class Real >
ChFrame< Real > operator* (const ChCoordsys< Real > &Ca, const ChFrame< Real > &Fb)
 The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChCoordsys frame_B is a ChFrame Returns a ChFrame. More...
 
template<class Real >
ChCoordsys< Real > operator>> (const ChCoordsys< Real > &Ca, const ChFrame< Real > &Fb)
 The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChCoordsys frame_B is a ChFrame Returns a ChCoordsys. More...
 
template<class Real >
ChFrame< Real > operator>> (const ChFrame< Real > &Fa, const ChCoordsys< Real > &Cb)
 The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrame frame_B is a ChCoordsys Returns a ChFrame. More...
 
template<class Real >
ChVector3< Real > operator* (const ChFrame< Real > &Fa, const ChVector3< Real > &vb)
 The '*' operator that transforms 'mixed' types: vector_C = frame_A * vector_B; where frame_A is a ChFrame vector_B is a ChVector Returns a ChVector. More...
 
template<class Real >
ChFrame< Real > operator* (const ChVector3< Real > &va, const ChFrame< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChFrame. More...
 
template<class Real >
ChVector3< Real > operator>> (const ChVector3< Real > &va, const ChFrame< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: vector_C = vector_A >> frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChVector. More...
 
template<class Real >
ChFrame< Real > operator>> (const ChFrame< Real > &Fa, const ChVector3< Real > &vb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChFrame frame_B is a ChVector Returns a ChFrame. More...
 
template<class Real >
ChQuaternion< Real > operator* (const ChFrame< Real > &Fa, const ChQuaternion< Real > &qb)
 The '*' operator that transforms 'mixed' types: quat_C = frame_A * quat_B; where frame_A is a ChFrame quat_B is a ChQuaternion Returns a ChQuaternion. More...
 
template<class Real >
ChFrame< Real > operator* (const ChQuaternion< Real > &qa, const ChFrame< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChFrame Returns a ChFrame. More...
 
template<class Real >
ChQuaternion< Real > operator>> (const ChQuaternion< Real > &qa, const ChFrame< Real > &Fb)
 The '>>' operator that transforms 'mixed' types: quat_C = quat_A >> frame_B; where quat_A is a ChQuaternion frame_B is a ChFrame Returns a ChQuaternion. More...
 
template<class Real >
ChFrame< Real > operator>> (const ChFrame< Real > &Fa, const ChQuaternion< Real > &qb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChFrame frame_B is a ChQuaternion Returns a ChFrame. More...
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChFrame< Real > &F)
 
template<class Real >
ChFrame< Real > operator* (const ChFrameMoving< Real > &Fa, const ChFrame< Real > &Fb)
 The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrameMoving frame_B is a ChFrame Returns a ChFrame. More...
 
template<class Real >
ChFrameMoving< Real > operator* (const ChFrame< Real > &Fa, const ChFrameMoving< Real > &Fb)
 The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrame frame_B is a ChFrameMoving Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator>> (const ChFrameMoving< Real > &Fa, const ChFrame< Real > &Fb)
 The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrameMoving frame_B is a ChFrame Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator* (const ChCoordsys< Real > &ca, const ChFrameMoving< Real > &Fb)
 The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChCoordsys frame_B is a ChFrameMoving Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator>> (const ChFrameMoving< Real > &Fa, const ChCoordsys< Real > &cb)
 The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrameMoving frame_B is a ChCoordsys Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator* (const ChVector3< Real > &va, const ChFrameMoving< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator>> (const ChFrameMoving< Real > &Fa, const ChVector3< Real > &vb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChFrame frame_B is a ChVector Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator* (const ChQuaternion< Real > &qa, const ChFrameMoving< Real > &Fb)
 The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChFrameMoving Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator>> (const ChFrameMoving< Real > &Fa, const ChQuaternion< Real > &qb)
 The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChFrameMoving frame_B is a ChQuaternion Returns a ChFrameMoving. More...
 
void SetChronoDataPath (const std::string &path)
 Set the path to the Chrono data directory (ATTENTION: not thread safe).
 
const std::string & GetChronoDataPath ()
 Obtain the current path to the Chrono data directory (thread safe).
 
std::string GetChronoDataFile (const std::string &filename)
 Get the full path to the specified filename, given relative to the Chrono data directory (thread safe).
 
void SetChronoOutputPath (const std::string &path)
 Set the path to the Chrono output directory (ATTENTION: not thread safe).
 
const std::string & GetChronoOutputPath ()
 Obtain the path to the output directory for Chrono demos.
 
void PasteMatrix (ChSparseMatrix &matrTo, ChMatrixConstRef matrFrom, int start_row, int start_col, bool overwrite=true)
 Paste a given matrix into a sparse matrix at position (start_row, start_col). More...
 
template<typename T = double>
ChVectorDynamic< T > SliceVector (ChVectorConstRef v, ChArrayConstRef< int > indices)
 Utility function for slicing a vector based on an array of indices. More...
 
void StreamOut (ChMatrixConstRef A, std::ostream &stream)
 Serialization of a dense matrix or vector into an ASCII stream (e.g. a file).
 
void StreamOut (ChSparseMatrix &mat, std::ostream &stream, bool one_indexed=false)
 Serialization of a sparse matrix to an ASCII stream (e.g., a file) in COO sparse matrix format. More...
 
template<typename Real >
ChVector3< Real > operator* (const Eigen::Transpose< Eigen::Matrix< Real, 3, 3, Eigen::RowMajor >> &A, const ChVector3< Real > &v)
 Multiply a transposed 3x3 matrix with a vector.
 
template<typename Real >
ChVector3< Real > operator* (const Eigen::Transpose< const Eigen::Matrix< Real, 3, 3, Eigen::RowMajor >> &A, const ChVector3< Real > &v)
 Multiply a transposed const 3x3 matrix with a vector.
 
template<class Real >
ChMatrix33< Real > TensorProduct (const ChVector3< Real > &vA, const ChVector3< Real > &vB)
 Return the outer product (a 3x3 matrix) of two vectors.
 
template<typename T , typename U >
ChVector3< T > operator* (const ChMatrix34< T > &A, const ChQuaternion< U > &q)
 Multiply a 3x4 matrix with a quaternion and return a 3d vector.
 
template<typename T , typename U >
ChQuaternion< T > operator* (const ChMatrix43< T > &A, const ChVector3< U > &v)
 Multiply a 4x3 matrix with a 3d vector and return a quaternion.
 
template<typename T , typename U >
ChQuaternion< T > operator* (const Eigen::Transpose< Eigen::Matrix< T, 3, 4, Eigen::RowMajor >> &A, const ChVector3< U > &v)
 Multiply the transpose of a 3x4 matrix with a 3d vector and return a quaternion.
 
template<typename T , typename U >
ChQuaternion< T > operator* (const ChMatrix44< T > &A, const ChQuaternion< U > &q)
 Multiply a 4x4 matrix with a quaternion and return a quaternion.
 
const ChQuaterniond Q_ROTATE_Y_TO_X (1/CH_SQRT_2, 0, 0, -1/CH_SQRT_2)
 
const ChQuaterniond Q_ROTATE_Y_TO_Z (1/CH_SQRT_2, 1/CH_SQRT_2, 0, 0)
 
const ChQuaterniond Q_ROTATE_X_TO_Y (1/CH_SQRT_2, 0, 0, 1/CH_SQRT_2)
 
const ChQuaterniond Q_ROTATE_X_TO_Z (1/CH_SQRT_2, 0, -1/CH_SQRT_2, 0)
 
const ChQuaterniond Q_ROTATE_Z_TO_Y (1/CH_SQRT_2, -1/CH_SQRT_2, 0, 0)
 
const ChQuaterniond Q_ROTATE_Z_TO_X (1/CH_SQRT_2, 0, 1/CH_SQRT_2, 0)
 
bool Qequal (const ChQuaterniond &qa, const ChQuaterniond &qb)
 Check if two quaternions are equal.
 
bool Qnotnull (const ChQuaterniond &qa)
 Check if quaternion is not null.
 
double Qlength (const ChQuaterniond &q)
 
ChQuaterniond Qscale (const ChQuaterniond &q, double fact)
 
ChQuaterniond Qadd (const ChQuaterniond &qa, const ChQuaterniond &qb)
 
ChQuaterniond Qsub (const ChQuaterniond &qa, const ChQuaterniond &qb)
 
ChQuaterniond Qnorm (const ChQuaterniond &q)
 Return the norm two of the quaternion. Euler's parameters have norm = 1.
 
ChQuaterniond Qconjugate (const ChQuaterniond &q)
 Return the conjugate of the quaternion [s,v1,v2,v3] is [s,-v1,-v2,-v3].
 
ChQuaterniond Qcross (const ChQuaterniond &qa, const ChQuaterniond &qb)
 Return the product of two quaternions. It is non-commutative (like cross product in vectors).
 
ChQuaterniond QuatDtFromAngVelAbs (const ChVector3d &w, const ChQuaterniond &q)
 Get the quaternion time derivative from the vector of angular speed, with w specified in absolute coords.
 
ChQuaterniond QuatDtFromAngVelRel (const ChVector3d &w, const ChQuaterniond &q)
 Get the quaternion time derivative from the vector of angular speed, with w specified in local coords.
 
ChQuaterniond QuatDt2FromAngAccAbs (const ChVector3d &a, const ChQuaterniond &q, const ChQuaterniond &q_dt)
 Get the quaternion first derivative from the vector of angular acceleration with a specified in absolute coords.
 
ChQuaterniond QuatDt2FromAngAccRel (const ChVector3d &a, const ChQuaterniond &q, const ChQuaterniond &q_dt)
 Get the quaternion second derivative from the vector of angular acceleration with a specified in relative coords.
 
ChQuaterniond QuatFromImaginary (const ChVector3d &imm)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChQuaterniond QuatDtFromImaginary (const ChVector3d &im_dt, const ChQuaterniond &q)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion time derivative, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChQuaterniond QuatDt2FromImaginary (const ChVector3d &im_dtdt, const ChQuaterniond &q, const ChQuaterniond &q_dt)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion second time derivative, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChVector3d VaxisXfromQuat (const ChQuaterniond &quat)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChQuaternion< Real > &q)
 Insertion of quaternion to output stream.
 
AngleSet AngleSetFromAngleSet (RotRepresentation to_seq, const AngleSet &set)
 Convert from one set of Euler or Cardan angles to another.
 
ChVector3d RodriguesFromAngleSet (const AngleSet &set)
 Convert from a set of Euler angles to Rodrigues parameters.
 
AngleSet AngleSetFromRodrigues (RotRepresentation to_seq, const ChVector3d &params)
 Convert from Rodrigues parameters to a set of Euler angles.
 
AngleAxis AngleAxisFromQuat (const ChQuaterniond &q)
 Convert from a quaternion to an angle-axis pair.
 
ChQuaterniond QuatFromAngleAxis (double angle, const ChVector3d &axis)
 Convert from an angle and an axis to a quaternion. More...
 
ChQuaterniond QuatFromAngleAxis (const AngleAxis &angle_axis)
 Convert from an angle-axis pair to a quaternion. More...
 
ChQuaterniond QuatDtFromAngleAxis (const ChQuaterniond &quat, double angle_dt, const ChVector3d &axis)
 Convert from a speed of rotation and an axis to a quaternion derivative. More...
 
ChQuaterniond QuatDt2FromAngleAxis (double angle_dtdt, const ChVector3d &axis, const ChQuaterniond &q, const ChQuaterniond &q_dt)
 Convert from a rotation acceleration and an axis to a quaternion second derivative. More...
 
ChQuaterniond QuatFromAngleX (double angle)
 Convert from a rotation about X axis to a quaternion.
 
ChQuaterniond QuatFromAngleY (double angle)
 Convert from a rotation about Y axis to a quaternion.
 
ChQuaterniond QuatFromAngleZ (double angle)
 Convert from a rotation about Z axis to a quaternion.
 
ChVector3d RotVecFromQuat (const ChQuaterniond &q)
 Convert from a quaternion to a rotation vector.
 
ChQuaterniond QuatFromRotVec (const ChVector3d &vec)
 Convert from a rotation vector to a quaternion.
 
ChVector3d RodriguesFromQuat (const ChQuaterniond &q)
 Convert from a quaternion to Rodrigues parameters.
 
ChQuaterniond QuatFromRodrigues (const ChVector3d &params)
 Convert from Rodrigues parameters to a quaternion.
 
ChQuaterniond QuatDtFromRodrigues (const ChVector3d &params, const ChQuaterniond &q)
 Convert from a set of Rodrigues parameter derivatives to a quaternion derivative.
 
ChQuaterniond QuatDt2FromRodrigues (const ChVector3d &params, const ChQuaterniond &q)
 Convert a set of Rodrigues parameter second derivatives to a quaternion second derivative.
 
AngleSet AngleSetFromQuat (RotRepresentation to_seq, const ChQuaterniond &q)
 Convert from a quaternion to a set of Euler angles.
 
ChQuaterniond QuatFromAngleSet (const AngleSet &set)
 Convert from a set of Euler angles to a quaternion.
 
ChQuaterniond QuatDtFromAngleSet (const AngleSet &set, const ChQuaterniond &q)
 Convert from a set of Euler angle derivatives to a quaternion derivative.
 
ChQuaterniond QuatDt2FromAngleSet (const AngleSet &set, const ChQuaterniond &q)
 Convert from a set of Euler angle second derivatives to a quaternion second derivative.
 
ChQuaterniond QuatFromVec2Vec (const ChVector3d &start, const ChVector3d &end)
 Convert from a vector-to-vector rotation to a quaternion. More...
 
template<class RealA , class RealB >
RealA Vdot (const ChVector2< RealA > va, const ChVector2< RealB > vb)
 
template<class RealA >
void Vset (ChVector2< RealA > &v, RealA mx, RealA my)
 
template<class RealA , class RealB >
ChVector2< RealA > Vadd (const ChVector2< RealA > &va, const ChVector2< RealB > &vb)
 
template<class RealA , class RealB >
ChVector2< RealA > Vsub (const ChVector2< RealA > &va, const ChVector2< RealB > &vb)
 
template<class RealA , class RealB >
ChVector2< RealA > Vmul (const ChVector2< RealA > &va, RealB fact)
 
template<class RealA >
RealA Vlength (const ChVector2< RealA > &va)
 
template<class RealA >
ChVector2< RealA > Vnorm (const ChVector2< RealA > &va)
 
template<class RealA , class RealB >
bool Vequal (const ChVector2< RealA > &va, const ChVector2< RealB > &vb)
 
template<class RealA >
bool Vnotnull (const ChVector2< RealA > &va)
 
template<class RealA , class RealB >
ChVector2< RealA > Vrot (const ChVector2< RealA > &v, RealB angle)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChVector2< Real > &v)
 Insertion of a 2D vector to output stream.
 
template<class Real >
ChVector2< Real > operator* (const Real s, const ChVector2< Real > &V)
 Operator for scaling the vector by a scalar value, as s*V.
 
template<class RealA , class RealB >
RealA Vdot (const ChVector3< RealA > &va, const ChVector3< RealB > &vb)
 
template<class RealA >
void Vset (ChVector3< RealA > &v, RealA mx, RealA my, RealA mz)
 
template<class RealA , class RealB >
ChVector3< RealA > Vadd (const ChVector3< RealA > &va, const ChVector3< RealB > &vb)
 
template<class RealA , class RealB >
ChVector3< RealA > Vsub (const ChVector3< RealA > &va, const ChVector3< RealB > &vb)
 
template<class RealA , class RealB >
ChVector3< RealA > Vcross (const ChVector3< RealA > &va, const ChVector3< RealB > &vb)
 
template<class RealA , class RealB >
ChVector3< RealA > Vmul (const ChVector3< RealA > &va, RealB fact)
 
template<class RealA >
RealA Vlength (const ChVector3< RealA > &va)
 
template<class RealA >
ChVector3< RealA > Vnorm (const ChVector3< RealA > &va)
 
template<class RealA , class RealB >
bool Vequal (const ChVector3< RealA > &va, const ChVector3< RealB > &vb)
 
template<class RealA >
bool Vnotnull (const ChVector3< RealA > &va)
 
template<class RealA >
ChVector3< RealA > Vmin (const ChVector3< RealA > &va, const ChVector3< RealA > &vb)
 
template<class RealA >
ChVector3< RealA > Vmax (const ChVector3< RealA > &va, const ChVector3< RealA > &vb)
 
template<class RealA >
double VangleYZplane (const ChVector3< RealA > &va)
 
template<class RealA >
double VangleYZplaneNorm (const ChVector3< RealA > &va)
 
template<class RealA >
double VangleRX (const ChVector3< RealA > &va)
 
template<class RealA >
ChVector3< RealA > VfromPolar (double norm_angle, double pol_angle)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChVector3< Real > &v)
 Insertion of a 3D vector to output stream.
 
template<class Real >
ChVector3< Real > operator* (Real s, const ChVector3< Real > &V)
 Operator for scaling the vector by a scalar value, as s*V.
 
ChQuaternion SLERP (const ChQuaternion<> &qa, const ChQuaternion<> &qb, double t)
 
ChQuaternion QUADRANGLE (const ChQuaternion<> &q0, const ChQuaternion<> &q1, const ChQuaternion<> &q2)
 
bool InterpolateAndInsert (ChTriangleMeshConnected &mesh, int ibuffer, int i1, int i2, int &created_index)
 
template<typename Enumeration >
auto as_integer (Enumeration const value) -> typename std::underlying_type< Enumeration >::type
 Explicit conversion of scoped enumeration to int (e.g. for streaming).
 
template<typename InputIterator1 , typename InputIterator2 , typename OutputIterator >
OutputIterator Thrust_Expand (InputIterator1 first1, InputIterator1 last1, InputIterator2 first2, OutputIterator output)
 Utility to expand an input sequence by replicating each element a variable number of times. More...
 
CUDA_HOST_DEVICE ChApi real3 DotMM (const real *M)
 
CUDA_HOST_DEVICE ChApi real3 DotMM (const real *M, const real *N)
 
CUDA_HOST_DEVICE ChApi Mat33 MulMM (const real *M, const real *N)
 
CUDA_HOST_DEVICE ChApi Mat33 MulM_TM (const real *M, const real *N)
 
CUDA_HOST_DEVICE ChApi real3 MulMV (const real *M, const real *N)
 
CUDA_HOST_DEVICE ChApi Mat33 OuterProductVV (const real *A, const real *B)
 
CUDA_HOST_DEVICE ChApi Mat33 ScaleMat (const real *M, const real b)
 
CUDA_HOST_DEVICE ChApi SymMat33 NormalEquations (const real *A)
 
CUDA_HOST_DEVICE ChApi Mat33 MAbs (const real *M)
 
CUDA_HOST_DEVICE ChApi real3 operator* (const Mat33 &M, const real3 &v)
 
CUDA_HOST_DEVICE ChApi Mat33 operator* (const Mat33 &N, const real scale)
 
CUDA_HOST_DEVICE ChApi Mat33 operator* (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi Mat33 operator+ (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi Mat33 operator- (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT real CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT (+, Mat33, Mat33) CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT(-
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT real CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE ChApi Mat33 CUDA_HOST_DEVICE ChApi Mat33 operator- (const Mat33 &M)
 
CUDA_HOST_DEVICE ChApi Mat33 operator* (const real s, const Mat33 &a)
 
CUDA_HOST_DEVICE ChApi Mat33 Abs (const Mat33 &m)
 
CUDA_HOST_DEVICE ChApi Mat33 SkewSymmetric (const real3 &r)
 
CUDA_HOST_DEVICE ChApi Mat33 SkewSymmetricAlt (const real3 &r)
 
CUDA_HOST_DEVICE ChApi Mat33 MultTranspose (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi Mat33 TransposeMult (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi Mat33 Transpose (const Mat33 &a)
 
CUDA_HOST_DEVICE ChApi real Trace (const Mat33 &m)
 
CUDA_HOST_DEVICE ChApi Mat33 OuterProduct (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real InnerProduct (const Mat33 &A, const Mat33 &B)
 
CUDA_HOST_DEVICE ChApi Mat33 Adjoint (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi Mat33 AdjointTranspose (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi real Determinant (const Mat33 &m)
 
CUDA_HOST_DEVICE ChApi Mat33 Inverse (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi Mat33 InverseTranspose (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi Mat33 InverseUnsafe (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi Mat33 InverseTransposeUnsafe (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi real Norm (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi real NormSq (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi real DoubleDot (const Mat33 &A, const Mat33 &B)
 
CUDA_HOST_DEVICE ChApi real3 LargestColumnNormalized (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi Mat33 operator* (const DiagMat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE ChApi real3 operator* (const DiagMat33 &M, const real3 &v)
 
CUDA_HOST_DEVICE ChApi SymMat33 operator- (const SymMat33 &M, const real &v)
 
CUDA_HOST_DEVICE ChApi SymMat33 CofactorMatrix (const SymMat33 &A)
 
CUDA_HOST_DEVICE ChApi real3 LargestColumnNormalized (const SymMat33 &A)
 
CUDA_HOST_DEVICE ChApi SymMat33 NormalEquationsMatrix (const Mat33 &A)
 
CUDA_HOST_DEVICE ChApi real3 operator* (const Mat32 &M, const real2 &v)
 
CUDA_HOST_DEVICE ChApi Mat32 operator* (const SymMat33 &M, const Mat32 &N)
 
CUDA_HOST_DEVICE ChApi SymMat22 operator- (const SymMat22 &M, const real &v)
 
CUDA_HOST_DEVICE ChApi SymMat22 CofactorMatrix (const SymMat22 &A)
 
CUDA_HOST_DEVICE ChApi real2 LargestColumnNormalized (const SymMat22 &A)
 
CUDA_HOST_DEVICE ChApi SymMat22 TransposeTimesWithSymmetricResult (const Mat32 &A, const Mat32 &B)
 
CUDA_HOST_DEVICE ChApi SymMat22 ConjugateWithTranspose (const Mat32 &A, const SymMat33 &B)
 
CUDA_HOST_DEVICE ChApi void Print (const Mat33 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void Print (const Mat32 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void Print (const SymMat33 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void Print (const SymMat22 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void PrintLine (const Mat33 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void PrintLine (const Mat32 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void PrintLine (const SymMat33 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi void PrintLine (const SymMat22 &A, const char *name)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT_PROTO real CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT_PROTO Mat33 CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT_PROTO (+, Mat33, Mat33) CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT_PROTO(-
 
CUDA_HOST_DEVICE ChApi vec3 operator- (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE ChApi vec3 operator- (const vec3 &a, const int &b)
 
CUDA_HOST_DEVICE ChApi vec3 operator+ (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE ChApi vec3 operator+ (const vec3 &a, const int &b)
 
CUDA_HOST_DEVICE ChApi vec3 Clamp (const vec3 &a, const vec3 &clamp_min, const vec3 &clamp_max)
 
CUDA_HOST_DEVICE ChApi vec3 Max (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE ChApi vec3 Min (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE real Lerp (const real &start, const real &end, const real &t)
 
template<typename T >
CUDA_HOST_DEVICE void Swap (T &a, T &b)
 
template<typename T >
CUDA_HOST_DEVICE void Sort (T &a, T &b, T &c)
 
template<typename T >
CUDA_HOST_DEVICE void SwapIfGreater (T &a, T &b)
 
CUDA_HOST_DEVICE real Clamp (real x, real low, real high)
 Clamps a given value a between user specified minimum and maximum values.
 
CUDA_HOST_DEVICE void ClampValue (real &x, real low, real high)
 Clamps a given value a between user specified minimum and maximum values.
 
CUDA_HOST_DEVICE real ClampMin (real x, real low)
 
CUDA_HOST_DEVICE real ClampMax (real x, real high)
 
CUDA_HOST_DEVICE real2 operator+ (const real2 &a, real b)
 
CUDA_HOST_DEVICE real2 operator- (const real2 &a, real b)
 
CUDA_HOST_DEVICE real2 operator* (const real2 &a, real b)
 
CUDA_HOST_DEVICE real2 operator/ (const real2 &a, real b)
 
CUDA_HOST_DEVICE real2 operator+ (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real2 operator- (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real2 operator* (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real2 operator/ (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real2 operator- (const real2 &a)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (/, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (+, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (-, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (/, real2, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (+, real2, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL (-, real2, real2)
 
CUDA_HOST_DEVICE real2 operator* (real lhs, const real2 &rhs)
 
CUDA_HOST_DEVICE bool operator== (const real2 &lhs, const real2 &rhs)
 
CUDA_HOST_DEVICE real2 Max (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real2 Min (const real2 &a, const real2 &b)
 
CUDA_HOST_DEVICE real Dot (const real2 &v1, const real2 &v2)
 
CUDA_HOST_DEVICE real Dot (const real2 &v)
 
CUDA_HOST_DEVICE real Length2 (const real2 &v1)
 
CUDA_HOST_DEVICE real2 Normalize (const real2 &v1)
 
CUDA_HOST_DEVICE void Print (real2 v, const char *name)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (/, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (+, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (-, real, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (/, real2, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (+, real2, real2)
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_PROTO (-, real2, real2)
 
CUDA_HOST_DEVICE ChApi real3 Set3 (real x)
 
CUDA_HOST_DEVICE ChApi real3 Set3 (real x, real y, real z)
 
CUDA_HOST_DEVICE ChApi real3 operator+ (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 operator- (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 operator* (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 operator/ (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 operator+ (const real3 &a, real b)
 
CUDA_HOST_DEVICE ChApi real3 operator- (const real3 &a, real b)
 
CUDA_HOST_DEVICE ChApi real3 operator* (const real3 &a, real b)
 
CUDA_HOST_DEVICE ChApi real3 operator/ (const real3 &a, real b)
 
CUDA_HOST_DEVICE ChApi real3 operator* (real lhs, const real3 &rhs)
 
CUDA_HOST_DEVICE ChApi real3 operator/ (real lhs, const real3 &rhs)
 
CUDA_HOST_DEVICE ChApi real3 operator- (const real3 &a)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (/, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (+, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (-, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (/, real3, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (+, real3, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (-, real3, real3)
 
CUDA_HOST_DEVICE ChApi real Dot (const real3 &v1, const real3 &v2)
 
CUDA_HOST_DEVICE ChApi real Dot (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 Normalize (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real Length (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 Sqrt (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 Cross (const real3 &b, const real3 &c)
 
CUDA_HOST_DEVICE ChApi real3 Abs (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 Sign (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 Max (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 Min (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 Max (const real3 &a, const real &b)
 
CUDA_HOST_DEVICE ChApi real3 Min (const real3 &a, const real &b)
 
CUDA_HOST_DEVICE ChApi real Max (const real3 &a)
 
CUDA_HOST_DEVICE ChApi real Min (const real3 &a)
 
CUDA_HOST_DEVICE ChApi real Length2 (const real3 &v1)
 
CUDA_HOST_DEVICE ChApi real SafeLength (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 SafeNormalize (const real3 &v, const real3 &safe)
 
CUDA_HOST_DEVICE ChApi real3 Clamp (const real3 &a, const real3 &clamp_min, const real3 &clamp_max)
 
CUDA_HOST_DEVICE ChApi real3 Clamp (const real3 &v, real max_length)
 
CUDA_HOST_DEVICE ChApi bool operator< (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi bool operator> (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi bool operator== (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE ChApi real3 Round (const real3 &v)
 
CUDA_HOST_DEVICE ChApi bool IsZero (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 OrthogonalVector (const real3 &v)
 
CUDA_HOST_DEVICE ChApi real3 UnitOrthogonalVector (const real3 &v)
 
CUDA_HOST_DEVICE ChApi void Print (real3 v, const char *name)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (/, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (+, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (-, real, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (/, real3, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (+, real3, real3)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (-, real3, real3)
 
CUDA_HOST_DEVICE ChApi void Sort (real &a, real &b, real &c)
 
CUDA_HOST_DEVICE ChApi real4 Set4 (real x)
 
CUDA_HOST_DEVICE ChApi real4 Set4 (real x, real y, real z, real w)
 
CUDA_HOST_DEVICE ChApi real4 operator+ (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE ChApi real4 operator- (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE ChApi real4 operator* (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE ChApi real4 operator/ (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE ChApi real4 operator+ (const real4 &a, real b)
 
CUDA_HOST_DEVICE ChApi real4 operator- (const real4 &a, real b)
 
CUDA_HOST_DEVICE ChApi real4 operator* (const real4 &a, real b)
 
CUDA_HOST_DEVICE ChApi real4 operator/ (const real4 &a, real b)
 
CUDA_HOST_DEVICE ChApi real4 operator- (const real4 &a)
 
CUDA_HOST_DEVICE ChApi real4 Dot4 (const real3 &v, const real3 &v1, const real3 &v2, const real3 &v3, const real3 &v4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (/, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (+, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (-, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (/, real4, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (+, real4, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL (-, real4, real4)
 
CUDA_HOST_DEVICE ChApi quaternion SetQ (real x)
 
CUDA_HOST_DEVICE ChApi quaternion SetQ (real w, real x, real y, real z)
 
CUDA_HOST_DEVICE ChApi quaternion operator+ (const quaternion &a, real b)
 
CUDA_HOST_DEVICE ChApi quaternion operator- (const quaternion &a, real b)
 
CUDA_HOST_DEVICE ChApi quaternion operator* (const quaternion &a, real b)
 
CUDA_HOST_DEVICE ChApi quaternion operator/ (const quaternion &a, real b)
 
CUDA_HOST_DEVICE ChApi quaternion operator- (const quaternion &a)
 
CUDA_HOST_DEVICE ChApi quaternion operator~ (const quaternion &a)
 
CUDA_HOST_DEVICE ChApi quaternion Inv (const quaternion &a)
 
CUDA_HOST_DEVICE ChApi real Dot (const quaternion &v1, const quaternion &v2)
 
CUDA_HOST_DEVICE ChApi real Dot (const quaternion &v)
 
CUDA_HOST_DEVICE ChApi quaternion Mult (const quaternion &a, const quaternion &b)
 
CUDA_HOST_DEVICE ChApi quaternion Normalize (const quaternion &v)
 
CUDA_HOST_DEVICE ChApi real3 Rotate (const real3 &v, const quaternion &q)
 
CUDA_HOST_DEVICE ChApi real3 RotateT (const real3 &v, const quaternion &q)
 
CUDA_HOST_DEVICE ChApi real3 AbsRotate (const quaternion &q, const real3 &v)
 
CUDA_HOST_DEVICE ChApi quaternion QuatFromAngleAxis (const real &angle, const real3 &axis)
 
CUDA_HOST_DEVICE ChApi real3 AMatU (const quaternion &q)
 
CUDA_HOST_DEVICE ChApi real3 AMatV (const quaternion &q)
 
CUDA_HOST_DEVICE ChApi real3 AMatW (const quaternion &q)
 
CUDA_HOST_DEVICE ChApi void Print (quaternion v, const char *name)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (/, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (+, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (-, real, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (/, real4, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (+, real4, real4)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_PROTO (-, real4, real4)
 
void swap (ChAssembly &first, ChAssembly &second)
 
template<class Tcont , class Titer >
void _RemoveAllContacts (std::list< Tcont * > &contactlist, Titer &lastcontact, int &n_added)
 
template<class Tcont , class Titer , class Ta , class Tb >
void _OptimalContactInsert (std::list< Tcont * > &contactlist, Titer &lastcontact, int &n_added, ChContactContainerNSC *container, Ta *objA, Tb *objB, const ChCollisionInfo &cinfo, const ChContactMaterialCompositeNSC &cmat)
 
template<class Tcont >
void _ReportAllContacts (std::list< Tcont * > &contactlist, ChContactContainer::ReportContactCallback *mcallback)
 
template<class Tcont >
void _ReportAllContactsRolling (std::list< Tcont * > &contactlist, ChContactContainer::ReportContactCallback *mcallback)
 
template<class Tcont >
void _ReportAllContactsNSC (std::list< Tcont * > &contactlist, ChContactContainerNSC::ReportContactCallbackNSC *mcallback)
 
template<class Tcont >
void _ReportAllContactsRollingNSC (std::list< Tcont * > &contactlist, ChContactContainerNSC::ReportContactCallbackNSC *mcallback)
 
template<class Tcont >
void _IntStateGatherReactions (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off_L, ChVectorDynamic<> &L, const int stride)
 
template<class Tcont >
void _IntStateScatterReactions (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off_L, const ChVectorDynamic<> &L, const int stride)
 
template<class Tcont >
void _IntLoadResidual_CqL (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off_L, ChVectorDynamic<> &R, const ChVectorDynamic<> &L, const double c, const int stride)
 
template<class Tcont >
void _IntLoadConstraint_C (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off, ChVectorDynamic<> &Qc, const double c, bool do_clamp, double recovery_clamp, const int stride)
 
template<class Tcont >
void _IntToDescriptor (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off_v, const ChStateDelta &v, const ChVectorDynamic<> &R, const unsigned int off_L, const ChVectorDynamic<> &L, const ChVectorDynamic<> &Qc, const int stride)
 
template<class Tcont >
void _IntFromDescriptor (unsigned int &coffset, std::list< Tcont * > &contactlist, const unsigned int off_v, ChStateDelta &v, const unsigned int off_L, ChVectorDynamic<> &L, const int stride)
 
template<class Tcont >
void _InjectConstraints (std::list< Tcont * > &contactlist, ChSystemDescriptor &descriptor)
 
template<class Tcont >
void _ConstraintsBiReset (std::list< Tcont * > &contactlist)
 
template<class Tcont >
void _ConstraintsBiLoad_C (std::list< Tcont * > &contactlist, double factor, double recovery_clamp, bool do_clamp)
 
template<class Tcont >
void _ConstraintsFetch_react (std::list< Tcont * > &contactlist, double factor)
 
template<class Tcont , class Titer , class Ta , class Tb >
void _OptimalContactInsert (std::list< Tcont * > &contactlist, Titer &lastcontact, int &n_added, ChContactContainerSMC *container, Ta *objA, Tb *objB, const ChCollisionInfo &cinfo, const ChContactMaterialCompositeSMC &cmat)
 
template<class Tcont >
void _IntLoadResidual_F (std::list< Tcont * > &contactlist, ChVectorDynamic<> &R, const double c)
 
template<class Tcont >
void _KRMmatricesLoad (std::list< Tcont * > contactlist, double Kfactor, double Rfactor)
 
template<class Tcont >
void _InjectKRMmatrices (std::list< Tcont * > contactlist, ChSystemDescriptor &descriptor)
 
 CH_FACTORY_REGISTER (ChContactMaterialData)
 
 CH_FACTORY_REGISTER (ChContactMaterialComposite)
 
 CH_FACTORY_REGISTER (ChContactMaterialCompositionStrategy)
 
void Transform_Cq_to_Cqw_row (const ChMatrixNM< double, 7, BODY_QDOF > &mCq, int qrow, ChMatrixRef mCqw, int qwrow, const ChGlMatrix34<> &Gl)
 
template<class T >
ChNameValue< T > make_ChNameValue (const std::string &auto_name, const T &t, const std::string &custom_name, char flags=0, ChCausalityType causality=ChCausalityType::local, ChVariabilityType variability=ChVariabilityType::continuous)
 
template<class T >
ChNameValue< T > make_ChNameValue (const std::string &auto_name, const T &t, char flags=0, ChCausalityType causality=ChCausalityType::local, ChVariabilityType variability=ChVariabilityType::continuous)
 
template<class T >
void StreamSwapBytes (T *ptData)
 Templated function for swapping bytes of objects of type 'T', for arbitrary T type. More...
 
 CH_UPCASTING (ChSolverVI, ChSolver) ChIterativeSolverVI
 
ChState operator+ (const ChState &y, const ChStateDelta &Dy)
 Custom operator "+" that takes care of incremental update of a state y by an increment Dy. More...
 
ChStateoperator+= (ChState &y, const ChStateDelta &Dy)
 
ChState operator+ (const ChStateDelta &Dy, const ChState &y)
 Custom operator "+" that takes care of incremental update of a state y by an increment Dy "y_new = Dy + y", invokes the specialized StateIncrement() in the ChIntegrable. More...
 
ChState operator- (const ChState &y, const ChStateDelta &Dy)
 Custom operator "-" that takes care of incremental update of a state y by an increment Dy. More...
 
ChStateoperator-= (ChState &y, const ChStateDelta &Dy)
 
ChState operator- (const ChStateDelta &Dy, const ChState &y)
 Custom operator "-" that takes care of incremental update of a state y by an increment Dy "y_new = Dy - y", invokes the specialized StateIncrement() in the ChIntegrable. More...
 
template<typename T >
void ChClampValue (T &value, T limitMin, T limitMax)
 Clamp and modify the specified value to lie within the given limits.
 
template<typename T >
ChClamp (T value, T limitMin, T limitMax)
 Clamp the specified value to lie within the given limits.
 
template<typename T >
int ChSignum (T x)
 Signum function.
 
CH_MULTICORE_API void Orthogonalize (const real3 &Vx, real3 &Vy, real3 &Vz)
 
CH_MULTICORE_API void Compute_Jacobian (const quaternion &quat, const real3 &U, const real3 &V, const real3 &W, const real3 &point, real3 &T1, real3 &T2, real3 &T3)
 
CH_MULTICORE_API void Compute_Jacobian_Rolling (const quaternion &quat, const real3 &U, const real3 &V, const real3 &W, real3 &T1, real3 &T2, real3 &T3)
 
CH_MULTICORE_API bool Cone_generalized_rigid (real &gamma_n, real &gamma_u, real &gamma_v, real mu)
 
CH_MULTICORE_API bool Cone_single_rigid (real &gamma_n, real &gamma_s, real mu)
 
CH_MULTICORE_API void AppendRigidFluidBoundary (const real contact_mu, const uint num_fluid_bodies, const uint body_offset, const uint start_boundary, ChMulticoreDataManager *data_manager)
 
CH_MULTICORE_API void ProjectRigidFluidBoundary (const real contact_mu, const real contact_cohesion, const uint num_fluid_bodies, const uint start_boundary, real *gamma, ChMulticoreDataManager *data_manager)
 
CH_MULTICORE_API void ComplianceRigidFluidBoundary (const real contact_mu, const real contact_compliance, const real alpha, const uint start_boundary, ChMulticoreDataManager *data_manager)
 
CH_MULTICORE_API void CorrectionRigidFluidBoundary (const real contact_mu, const real contact_cohesion, const real alpha, const real contact_recovery_speed, const uint num_fluid_bodies, const uint start_boundary, ChMulticoreDataManager *data_manager)
 
CH_MULTICORE_API void BuildRigidFluidBoundary (const real contact_mu, const uint num_fluid_bodies, const uint body_offset, const uint start_boundary, ChMulticoreDataManager *data_manager)
 
void MPM_Initialize (MPM_Settings &settings, std::vector< float > &positions)
 
void MPM_Solve (MPM_Settings &settings, std::vector< float > &positions, std::vector< float > &velocities)
 
void MPM_UpdateDeformationGradient (MPM_Settings &settings, std::vector< float > &positions, std::vector< float > &velocities, std::vector< float > &jejp)
 
CUDA_HOST_DEVICE float Clamp (float x, float low, float high)
 
CUDA_HOST_DEVICE OPERATOR_EQUALSALT float CUDA_HOST_DEVICE OPERATOR_EQUALSALT Mat33f CUDA_HOST_DEVICE OPERATOR_EQUALSALT (+, Mat33f, Mat33f) CUDA_HOST_DEVICE OPERATOR_EQUALSALT(-
 
real N (const real &dist, const real &h)
 
real cubic_spline (const real &dist, const real &h)
 
real3 grad_cubic_spline (const real3 &dist, const real d, const real &h)
 
real poly6 (const real &dist, const real &h)
 
real3 grad_poly6 (const real3 &xij, const real d, const real &h)
 
real spiky (const real &dist, const real &h)
 
real3 grad_spiky (const real3 &xij, const real dist, const real &h)
 
real unormalized_spiky (const real &dist, const real &h)
 
real3 unormalized_grad_spiky (const real3 &xij, const real d, const real &h)
 
real3 viscosity (const real3 &xij, const real d, const real &h)
 
real3 grad2_viscosity (const real3 &xij, const real d, const real &h)
 
real kernel (const real &dist, const real &h)
 
real grad2_poly6 (const real &dist, const real &h)
 
BilateralType GetBilateralType (ChPhysicsItem *item)
 

Variables

auto inverted
 
const ChCoordsysd CSYSNULL (ChVector3d(0, 0, 0), ChQuaterniond(0, 0, 0, 0))
 
const ChCoordsysd CSYSNORM (ChVector3d(0, 0, 0), ChQuaterniond(1, 0, 0, 0))
 
ChQuadratureTables static_tables (1, CH_QUADRATURE_STATIC_TABLES)
 
ChQuadratureTablesTriangle static_tables_triangle
 
ChQuadratureTablesTetrahedron static_tables_tetrahedron
 
const ChQuaterniond QNULL (0., 0., 0., 0.)
 Constant null quaternion: {0, 0, 0, 0}.
 
const ChQuaterniond QUNIT (1., 0., 0., 0.)
 Constant unit quaternion: {1, 0, 0, 0} , corresponds to no rotation (diagonal rotation matrix)
 
const ChQuaterniond Q_FLIP_AROUND_X (0., 1., 0., 0.)
 
const ChQuaterniond Q_FLIP_AROUND_Y (0., 0., 1., 0.)
 
const ChQuaterniond Q_FLIP_AROUND_Z (0., 0., 0., 1.)
 
const ChApi ChQuaterniond Q_ROTATE_Y_TO_X
 
const ChApi ChQuaterniond Q_ROTATE_Y_TO_Z
 
const ChApi ChQuaterniond Q_ROTATE_X_TO_Y
 
const ChApi ChQuaterniond Q_ROTATE_X_TO_Z
 
const ChApi ChQuaterniond Q_ROTATE_Z_TO_Y
 
const ChApi ChQuaterniond Q_ROTATE_Z_TO_X
 
const ChVector3d VNULL (0., 0., 0.)
 
const ChVector3d VECT_X (1., 0., 0.)
 
const ChVector3d VECT_Y (0., 1., 0.)
 
const ChVector3d VECT_Z (0., 0., 1.)
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT real CUDA_HOST_DEVICE ChApi OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE ChApi Mat33
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL * real2
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL * real3
 
CUDA_HOST_DEVICE ChApi OPERATOR_EQUALS_IMPL * real4
 
const int BODY_DOF = 6
 degrees of freedom of body in 3d space
 
const int BODY_QDOF = 7
 degrees of freedom with quaternion rotation state
 
const int BODY_ROT = 3
 rotational dof in Newton dynamics
 
const std::unordered_map< chrono::ChVariabilityType, FmuVariable::VariabilityType > VariabilityType_conv
 
const std::unordered_map< chrono::ChCausalityType, FmuVariable::CausalityType > CausalityType_conv
 
CUDA_HOST_DEVICE OPERATOR_EQUALSALT float CUDA_HOST_DEVICE OPERATOR_EQUALSALT Mat33f CUDA_HOST_DEVICE Mat33f
 

Typedef Documentation

◆ ChCoordsysd

Alias for double-precision coordinate systems.

Instead of writing
   ChCoordsys<double> csys;
or
   ChCoordsys<> csys;
you can use:
   ChCoordsysd csys;

◆ ChCoordsysf

Alias for single-precision coordinate systems.

Instead of writing
   ChCoordsys<float> csys;
you can use:
   ChCoordsysf csys;

◆ ChFramed

typedef ChFrame<double> chrono::ChFramed

Alias for double-precision coordinate frames.

Instead of writing
   ChFrame<double> F;
or
   ChFrame<> F;
you can use:
   ChFramed F;

◆ ChFramef

typedef ChFrame<float> chrono::ChFramef

Alias for double-precision coordinate frames.

Instead of writing
   ChFrame<float> F;
you can use:
   ChFramef F;

◆ ChQuaterniond

Alias for double-precision quaternions.

Instead of writing
   ChQuaternion<double> q;
or
   ChQuaternion<> q;
you can use:
   ChQuaterniond q;

◆ ChQuaternionf

Alias for single-precision quaternions.

Instead of writing
   ChQuaternion<float> q;
you can use:
   ChQuaternionf q;

◆ ChVector2b

Alias for bool vectors.

Instead of writing
   ChVector2<bool> v;
you can use:
   ChVector2b v;

◆ ChVector2d

typedef ChVector2<double> chrono::ChVector2d

Alias for double-precision vectors.

Instead of writing
   ChVector2<double> v;
or
   ChVector2<> v;
you can use:
   ChVector2d v;

◆ ChVector2f

typedef ChVector2<float> chrono::ChVector2f

Alias for single-precision vectors.

Instead of writing
   ChVector2<float> v;
you can use:
   ChVector2f v;

◆ ChVector2i

Alias for integer vectors.

Instead of writing
   ChVector2<int> v;
you can use:
   ChVector2i v;

◆ ChVector3b

Alias for bool vectors.

Instead of writing
   ChVector3<bool> v;
you can use:
   ChVector3b v;

◆ ChVector3d

typedef ChVector3<double> chrono::ChVector3d

Alias for double-precision vectors.

Instead of writing
   ChVector3<double> v;
or
   ChVector3d v;
you can use:
   ChVector3d v;

◆ ChVector3f

typedef ChVector3<float> chrono::ChVector3f

Alias for single-precision vectors.

Instead of writing
   ChVector3<float> v;
you can use:
   ChVector3f v;

◆ ChVector3i

Alias for integer vectors.

Instead of writing
   ChVector3<int> v;
you can use:
   ChVector3i v;

Enumeration Type Documentation

◆ ChContactMethod

Enumeration of contact methods.

Enumerator
NSC 

non-smooth, constraint-based (a.k.a. rigid-body) contact

SMC 

smooth, penalty-based (a.k.a. soft-body) contact

◆ RotRepresentation

Definitions of various rotation representations for conversions.

Enumerator
ANGLE_AXIS 

angle-axis

ROTATION_VECTOR 

rotation vector (vector parallel with axis and length equal to angle)

EULER_ANGLES_ZXZ 

Euler angle sequence: Z - X' - Z'' (intrinsic rotations)

CARDAN_ANGLES_ZXY 

Cardan (Tait-Bryan) angle sequence: Z - X' - Y'' (intrinsic rotations)

CARDAN_ANGLES_ZYX 

Cardan (Tait-Bryan) angle sequence: Z - Y' - X'' (intrinsic rotations)

CARDAN_ANGLES_XYZ 

Cardan (Tait-Bryan) angle sequence: X - Y' - Z'' (intrinsic rotations)

RODRIGUES 

Rodrigues parameters.

Function Documentation

◆ getVoidPointer()

template<typename T , typename std::enable_if<!std::is_polymorphic< T >::value >::type * = nullptr>
void * chrono::getVoidPointer ( T *  ptr)

Type-erase pointer-to-object after making sure that it is pointing to the proper address Casting to void* through a static_cast leads to different results:

  • if the object is not polymorphic the result is just the type-erasure;
  • if the object is polymorphic, and the pointer is not of the most derived class, the resulting address (if the derived class has multiple inheritance) might not point to the original object address In this latter case, a dynamic_cast is required. However, the dynamic_cast is not possible for non-polymorphic classes, thus the need for a compile-time switch.

◆ operator*() [1/15]

template<class Real >
ChFrame<Real> chrono::operator* ( const ChCoordsys< Real > &  Ca,
const ChFrame< Real > &  Fb 
)

The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChCoordsys frame_B is a ChFrame Returns a ChFrame.

The effect is like applying the transformation frame_A to frame_B and get frame_C. Performance warning: this operator promotes frame_A to a temporary ChFrame.

◆ operator*() [2/15]

template<class Real >
ChFrameMoving<Real> chrono::operator* ( const ChCoordsys< Real > &  ca,
const ChFrameMoving< Real > &  Fb 
)

The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChCoordsys frame_B is a ChFrameMoving Returns a ChFrameMoving.

The effect is like applying the transformation frame_A to frame_B and get frame_C. Also speeds and accelerations are transformed. Performance warning: this operator promotes frame_A to a temporary ChFrameMoving.

◆ operator*() [3/15]

template<class Real >
ChQuaternion<Real> chrono::operator* ( const ChCoordsys< Real > &  Fa,
const ChQuaternion< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: quat_C = frame_A * quat_B; where frame_A is a ChCoordsys quat_B is a ChQuaternion Returns a ChQuaternion.

The effect is like applying the transformation frame_A to quat_B and get quat_C.

◆ operator*() [4/15]

template<class Real >
ChVector3<Real> chrono::operator* ( const ChCoordsys< Real > &  Fa,
const ChVector3< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: vector_C = frame_A * vector_B; where frame_A is a ChCoordsys vector_B is a ChVector Returns a ChVector.

The effect is like applying the transformation frame_A to vector_B and get vector_C.

◆ operator*() [5/15]

template<class Real >
ChCoordsys<Real> chrono::operator* ( const ChFrame< Real > &  Fa,
const ChCoordsys< Real > &  Cb 
)

The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrame frame_B is a ChCoordsys Returns a ChCoordsys.

The effect is like applying the transformation frame_A to frame_B and get frame_C.

◆ operator*() [6/15]

template<class Real >
ChFrameMoving<Real> chrono::operator* ( const ChFrame< Real > &  Fa,
const ChFrameMoving< Real > &  Fb 
)

The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrame frame_B is a ChFrameMoving Returns a ChFrameMoving.

The effect is like applying the transformation frame_A to frame_B and get frame_C. Also speeds and accelerations are transformed. Performance warning: this operator promotes frame_A to a temporary ChFrameMoving.

◆ operator*() [7/15]

template<class Real >
ChQuaternion<Real> chrono::operator* ( const ChFrame< Real > &  Fa,
const ChQuaternion< Real > &  qb 
)

The '*' operator that transforms 'mixed' types: quat_C = frame_A * quat_B; where frame_A is a ChFrame quat_B is a ChQuaternion Returns a ChQuaternion.

The effect is like applying the transformation frame_A to quat_B and get quat_C.

◆ operator*() [8/15]

template<class Real >
ChVector3<Real> chrono::operator* ( const ChFrame< Real > &  Fa,
const ChVector3< Real > &  vb 
)

The '*' operator that transforms 'mixed' types: vector_C = frame_A * vector_B; where frame_A is a ChFrame vector_B is a ChVector Returns a ChVector.

The effect is like applying the transformation frame_A to vector_B and get vector_C.

◆ operator*() [9/15]

template<class Real >
ChFrame<Real> chrono::operator* ( const ChFrameMoving< Real > &  Fa,
const ChFrame< Real > &  Fb 
)

The '*' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A * frame_B; where frame_A is a ChFrameMoving frame_B is a ChFrame Returns a ChFrame.

The effect is like applying the transformation frame_A to frame_B and get frame_C. Also speeds and accelerations are transformed.

◆ operator*() [10/15]

template<class Real >
ChCoordsys<Real> chrono::operator* ( const ChQuaternion< Real > &  Fa,
const ChCoordsys< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChCoordsys Returns a ChCoordsys.

The effect is like applying the rotation quat_A to frame_B and get frame_C.

◆ operator*() [11/15]

template<class Real >
ChFrame<Real> chrono::operator* ( const ChQuaternion< Real > &  qa,
const ChFrame< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChFrame Returns a ChFrame.

The effect is like applying the rotation quat_A to frame_B and get frame_C.

◆ operator*() [12/15]

template<class Real >
ChFrameMoving<Real> chrono::operator* ( const ChQuaternion< Real > &  qa,
const ChFrameMoving< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = quat_A * frame_B; where quat_A is a ChQuaternion frame_B is a ChFrameMoving Returns a ChFrameMoving.

The effect is like applying the rotation quat_A to frame_B and get frame_C. Also speeds and accelerations are rotated. Performance warning: this operator promotes quat_A to a temporary ChFrameMoving.

◆ operator*() [13/15]

template<class Real >
ChCoordsys<Real> chrono::operator* ( const ChVector3< Real > &  Fa,
const ChCoordsys< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChCoordsys Returns a ChCoordsys.

The effect is like applying the translation vector_A to frame_B and get frame_C.

◆ operator*() [14/15]

template<class Real >
ChFrame<Real> chrono::operator* ( const ChVector3< Real > &  va,
const ChFrame< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChFrame.

The effect is like applying the translation vector_A to frame_B and get frame_C.

◆ operator*() [15/15]

template<class Real >
ChFrameMoving<Real> chrono::operator* ( const ChVector3< Real > &  va,
const ChFrameMoving< Real > &  Fb 
)

The '*' operator that transforms 'mixed' types: frame_C = vector_A * frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChFrameMoving.

The effect is like applying the translation vector_A to frame_B and get frame_C.

◆ operator+() [1/2]

ChState chrono::operator+ ( const ChState y,
const ChStateDelta Dy 
)
inline

Custom operator "+" that takes care of incremental update of a state y by an increment Dy.

"y_new = y + Dy", invokes the specialized StateIncrement() in the ChIntegrable. If none is provided, this defaults to a simple vector sum

◆ operator+() [2/2]

ChState chrono::operator+ ( const ChStateDelta Dy,
const ChState y 
)
inline

Custom operator "+" that takes care of incremental update of a state y by an increment Dy "y_new = Dy + y", invokes the specialized StateIncrement() in the ChIntegrable.

If none is provided, this defaults to a simple vector sum

◆ operator-() [1/2]

ChState chrono::operator- ( const ChState y,
const ChStateDelta Dy 
)
inline

Custom operator "-" that takes care of incremental update of a state y by an increment Dy.

"y_new = y - Dy", invokes the specialized StateIncrement() in the ChIntegrable. If none is provided, this defaults to a simple vector sum

◆ operator-() [2/2]

ChState chrono::operator- ( const ChStateDelta Dy,
const ChState y 
)
inline

Custom operator "-" that takes care of incremental update of a state y by an increment Dy "y_new = Dy - y", invokes the specialized StateIncrement() in the ChIntegrable.

If none is provided, this defaults to a simple vector sum

◆ operator>>() [1/14]

template<class Real >
ChCoordsys<Real> chrono::operator>> ( const ChCoordsys< Real > &  Ca,
const ChFrame< Real > &  Fb 
)

The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChCoordsys frame_B is a ChFrame Returns a ChCoordsys.

The effect is like applying the transformation frame_B to frame_A and get frame_C.

◆ operator>>() [2/14]

template<class Real >
ChCoordsys<Real> chrono::operator>> ( const ChCoordsys< Real > &  Fa,
const ChQuaternion< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChCoordsys frame_B is a ChQuaternion Returns a ChCoordsys.

The effect is like applying the rotation quat_B to frame_A and get frame_C.

◆ operator>>() [3/14]

template<class Real >
ChCoordsys<Real> chrono::operator>> ( const ChCoordsys< Real > &  Fa,
const ChVector3< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChCoordsys vector_B is a ChVector Returns a ChCoordsys.

The effect is like applying the translation vector_B to frame_A and get frame_C.

◆ operator>>() [4/14]

template<class Real >
ChFrame<Real> chrono::operator>> ( const ChFrame< Real > &  Fa,
const ChCoordsys< Real > &  Cb 
)

The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrame frame_B is a ChCoordsys Returns a ChFrame.

The effect is like applying the transformation frame_B to frame_A and get frame_C. Performance warning: this operator promotes frame_B to a temporary ChFrame.

◆ operator>>() [5/14]

template<class Real >
ChFrame<Real> chrono::operator>> ( const ChFrame< Real > &  Fa,
const ChQuaternion< Real > &  qb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChFrame frame_B is a ChQuaternion Returns a ChFrame.

The effect is like applying the rotation quat_B to frame_A and get frame_C.

◆ operator>>() [6/14]

template<class Real >
ChFrame<Real> chrono::operator>> ( const ChFrame< Real > &  Fa,
const ChVector3< Real > &  vb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChFrame frame_B is a ChVector Returns a ChFrame.

The effect is like applying the translation vector_B to frame_A and get frame_C.

◆ operator>>() [7/14]

template<class Real >
ChFrameMoving<Real> chrono::operator>> ( const ChFrameMoving< Real > &  Fa,
const ChCoordsys< Real > &  cb 
)

The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrameMoving frame_B is a ChCoordsys Returns a ChFrameMoving.

The effect is like applying the transformation frame_B to frame_A and get frame_C. Also speeds and accelerations are transformed. Performance warning: this operator promotes frame_B to a temporary ChFrameMoving.

◆ operator>>() [8/14]

template<class Real >
ChFrameMoving<Real> chrono::operator>> ( const ChFrameMoving< Real > &  Fa,
const ChFrame< Real > &  Fb 
)

The '>>' operator that transforms a coordinate system of 'mixed' type: frame_C = frame_A >> frame_B; where frame_A is a ChFrameMoving frame_B is a ChFrame Returns a ChFrameMoving.

The effect is like applying the transformation frame_B to frame_A and get frame_C. Also speeds and accelerations are transformed. Performance warning: this operator promotes frame_B to a temporary ChFrameMoving.

◆ operator>>() [9/14]

template<class Real >
ChFrameMoving<Real> chrono::operator>> ( const ChFrameMoving< Real > &  Fa,
const ChQuaternion< Real > &  qb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> quat_B; where frame_A is a ChFrameMoving frame_B is a ChQuaternion Returns a ChFrameMoving.

The effect is like applying the rotation quat_B to frame_A and get frame_C. Also speeds and accelerations are rotated. Performance warning: this operator promotes quat_A to a temporary ChFrameMoving

◆ operator>>() [10/14]

template<class Real >
ChFrameMoving<Real> chrono::operator>> ( const ChFrameMoving< Real > &  Fa,
const ChVector3< Real > &  vb 
)

The '>>' operator that transforms 'mixed' types: frame_C = frame_A >> vector_B; where frame_A is a ChFrame frame_B is a ChVector Returns a ChFrameMoving.

The effect is like applying the translation vector_B to frame_A and get frame_C.

◆ operator>>() [11/14]

template<class Real >
ChQuaternion<Real> chrono::operator>> ( const ChQuaternion< Real > &  Fa,
const ChCoordsys< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: quat_C = quat_A >> frame_B; where quat_A is a ChQuaternion frame_B is a ChCoordsys Returns a ChQuaternion.

The effect is like applying the transformation frame_B to quat_A and get quat_C.

◆ operator>>() [12/14]

template<class Real >
ChQuaternion<Real> chrono::operator>> ( const ChQuaternion< Real > &  qa,
const ChFrame< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: quat_C = quat_A >> frame_B; where quat_A is a ChQuaternion frame_B is a ChFrame Returns a ChQuaternion.

The effect is like applying the transformation frame_B to quat_A and get quat_C.

◆ operator>>() [13/14]

template<class Real >
ChVector3<Real> chrono::operator>> ( const ChVector3< Real > &  Fa,
const ChCoordsys< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: vector_C = vector_A >> frame_B; where vector_A is a ChVector frame_B is a ChCoordsys Returns a ChVector.

The effect is like applying the transformation frame_B to frame_A and get frame_C.

◆ operator>>() [14/14]

template<class Real >
ChVector3<Real> chrono::operator>> ( const ChVector3< Real > &  va,
const ChFrame< Real > &  Fb 
)

The '>>' operator that transforms 'mixed' types: vector_C = vector_A >> frame_B; where vector_A is a ChVector frame_B is a ChFrame Returns a ChVector.

The effect is like applying the transformation frame_B to vector_A and get vector_C. For a sequence of transformations, i.e. a chain of coordinate systems, you can also write this (like you would do with a sequence of Denavitt-Hartemberg matrix multiplications, but in the opposite order...) new_v = old_v >> frame3to2 >> frame2to1 >> frame1to0; This operation is not commutative.

◆ QuatDt2FromAngleAxis()

ChApi ChQuaterniond chrono::QuatDt2FromAngleAxis ( double  angle_dtdt,
const ChVector3d axis,
const ChQuaterniond q,
const ChQuaterniond q_dt 
)

Convert from a rotation acceleration and an axis to a quaternion second derivative.

The rotation axis is assumed to be represented in absolute coordinates.

◆ QuatDt2FromImaginary()

ChApi ChQuaterniond chrono::QuatDt2FromImaginary ( const ChVector3d im_dtdt,
const ChQuaterniond q,
const ChQuaterniond q_dt 
)

Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion second time derivative, find the entire quaternion q = {e0, e1, e2, e3}.

Note: singularities are possible.

◆ QuatDtFromAngleAxis()

ChApi ChQuaterniond chrono::QuatDtFromAngleAxis ( const ChQuaterniond quat,
double  angle_dt,
const ChVector3d axis 
)

Convert from a speed of rotation and an axis to a quaternion derivative.

The rotation axis is assumed to be represented in absolute coordinates.

◆ QuatDtFromImaginary()

ChApi ChQuaterniond chrono::QuatDtFromImaginary ( const ChVector3d im_dt,
const ChQuaterniond q 
)

Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion time derivative, find the entire quaternion q = {e0, e1, e2, e3}.

Note: singularities are possible.

◆ QuatFromAngleAxis() [1/2]

ChApi ChQuaterniond chrono::QuatFromAngleAxis ( const AngleAxis angle_axis)

Convert from an angle-axis pair to a quaternion.

The axis is supposed to be fixed, i.e. it is constant during rotation. The 'axis' vector must be normalized.

◆ QuatFromAngleAxis() [2/2]

ChApi ChQuaterniond chrono::QuatFromAngleAxis ( double  angle,
const ChVector3d axis 
)

Convert from an angle and an axis to a quaternion.

The axis is supposed to be fixed, i.e. it is constant during rotation. The 'axis' vector must be normalized.

◆ QuatFromImaginary()

ChApi ChQuaterniond chrono::QuatFromImaginary ( const ChVector3d imm)

Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion, find the entire quaternion q = {e0, e1, e2, e3}.

Note: singularities are possible.

◆ QuatFromVec2Vec()

ChApi ChQuaterniond chrono::QuatFromVec2Vec ( const ChVector3d start,
const ChVector3d end 
)

Convert from a vector-to-vector rotation to a quaternion.

This quaternion represents the rotation that rotates the source vector to be aligned with the destination vector. The vectors do not need to be normalized.

◆ StreamSwapBytes()

template<class T >
void chrono::StreamSwapBytes ( T *  ptData)
inline

Templated function for swapping bytes of objects of type 'T', for arbitrary T type.

This is used for cross-platform compatibility when sharing objects between big-endian and little-endian memory models, depending on the microprocessor type.

◆ swap()

void chrono::swap ( ChAssembly first,
ChAssembly second 
)

Implemented as a friend (as opposed to a member function) so classes with a ChAssembly member can use ADL when implementing their own swap.

Variable Documentation

◆ CausalityType_conv

const std::unordered_map<chrono::ChCausalityType, FmuVariable::CausalityType> chrono::CausalityType_conv
Initial value:
= {
{chrono::ChCausalityType::parameter, FmuVariable::CausalityType::parameter},
{chrono::ChCausalityType::calculatedParameter, FmuVariable::CausalityType::calculatedParameter},
{chrono::ChCausalityType::input, FmuVariable::CausalityType::input},
{chrono::ChCausalityType::output, FmuVariable::CausalityType::output},
{chrono::ChCausalityType::local, FmuVariable::CausalityType::local},
{chrono::ChCausalityType::independent, FmuVariable::CausalityType::independent}}

◆ inverted

auto chrono::inverted
Initial value:
=
thrust::make_tuple(real3(+C_REAL_MAX, +C_REAL_MAX, +C_REAL_MAX), real3(-C_REAL_MAX, -C_REAL_MAX, -C_REAL_MAX), 0)

◆ VariabilityType_conv

const std::unordered_map<chrono::ChVariabilityType, FmuVariable::VariabilityType> chrono::VariabilityType_conv
Initial value:
= {
{chrono::ChVariabilityType::constant, FmuVariable::VariabilityType::constant},
{chrono::ChVariabilityType::fixed, FmuVariable::VariabilityType::fixed},
{chrono::ChVariabilityType::tunable, FmuVariable::VariabilityType::tunable},
{chrono::ChVariabilityType::discrete, FmuVariable::VariabilityType::discrete},
{chrono::ChVariabilityType::continuous, FmuVariable::VariabilityType::continuous}}