Description

Main namespace for the Chrono package.

Manager that handles all flatbuffer specifics.

of the vehicle

TODO: Look into ChArchive related files.

Namespaces

 AssemblyLevel
 Enumerations for assembly level.
 
 cascade
 Namespace with classes for the CASCADE module.
 
 collision
 Namespace with classes for collision detection.
 
 copter
 Namespace with classes for the Copter models.
 
 cosimul
 Namespace with classes for the cosimulation module.
 
 fea
 Namespace for FEA classes.
 
 fsi
 Namespace with classes for the FSI module.
 
 geometry
 Namespace for classes which represent basic geometric objects.
 
 gpu
 Namespace with classes for the Gpu module.
 
 irrlicht
 Namespace with classes for the Irrlicht module.
 
 opengl
 Namespace with classes for the Chrono::OpenGL 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.
 
 sensor
 Namespace for Chrono::Sensor.
 
 synchrono
 Namespace for SynChrono.
 
 utils
 Chrono core utilities.
 
 vehicle
 Namespace with classes for the VEHICLE module.
 
 viper
 Namespace with classes for the Viper model.
 

Classes

struct  BodyExchange
 Structure of data for sending a new body to a rank. More...
 
struct  BodyUpdate
 Structure of data for sending an update of an existing body to a rank. More...
 
class  Ch3DOFContainer
 Base class for containers of elements with 3 degrees of freedom (fluid nodes, particles, FEA nodes). More...
 
struct  Ch_enable_bitmask_operators
 Helper for adding bitmask operators | ^ & etc. More...
 
class  ChAparticle
 Class for a single particle clone in the ChParticlesClones cluster. More...
 
class  ChArchive
 This is a base class for archives with pointers to shared objects. More...
 
class  ChArchiveAsciiDump
 ASCII 'LOG' ARCHIVES (only output, for debugging etc.) More...
 
class  ChArchiveExplorer
 A helper class to provide some basic mechanism of C++ reflection (introspection). More...
 
class  ChArchiveIn
 This is a base class for serializing from archives. More...
 
class  ChArchiveInBinary
 This is a class for serializing from binary archives. 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
 This is a base class for serializing into archives. More...
 
class  ChArchiveOutBinary
 This is a class for serializing to binary archives. More...
 
class  ChArchiveOutJSON
 This is a class for serializing to JSON. More...
 
class  ChArchiveOutXML
 This is a class for serializing to XML file format. More...
 
class  ChAssembly
 Class for assemblies of items, for example ChBody, ChLink, ChMesh, etc. More...
 
class  ChAssemblyAnalysis
 Class for assembly analysis. More...
 
class  ChAsset
 Classes for adding user data (such as rendering shapes, reference to files) to ChPhysicsItem objects. More...
 
class  ChAssetLevel
 Class for grouping assets in a level. More...
 
class  ChBarrelShape
 Class for referencing a barrel shape (a lathed arc) that can be visualized in some way. 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  ChBinaryArchive
 Base class for streams (either in or out) based on binary formats. More...
 
class  ChBody
 Class for rigid bodies. More...
 
class  ChBodyAuxRef
 Class for rigid bodies with an auxiliary reference frame. More...
 
class  ChBodyEasyBox
 Easy-to-use class for quick creation of rigid bodies with a box shape. More...
 
class  ChBodyEasyClusterOfSpheres
 Easy-to-use class for quick creation of rigid bodies with a shape made of a cluster of spheres. More...
 
class  ChBodyEasyConvexHull
 Easy-to-use class for quick creation of rigid bodies with a convex hull shape. More...
 
class  ChBodyEasyConvexHullAuxRef
 Easy-to-use class for quick creation of rigid bodies with a convex hull shape, that has a REF csys distinct from the COG cys (this is helpful because in many cases the convex hull might have an offset barycenter with respect to the reference that we want to use for the body - otherwise use the simpler ChBodyEasyConvexHull) This class does automatically, at object creation: More...
 
class  ChBodyEasyCylinder
 Easy-to-use class for quick creation of rigid bodies with a cylindrical shape. More...
 
class  ChBodyEasyEllipsoid
 Easy-to-use class for quick creation of rigid bodies with an ellipsoid shape. More...
 
class  ChBodyEasyMesh
 Easy-to-use class for quick creation of rigid bodies with a triangle mesh shape, that has a REF csys distinct from the COG cys (this is helpful because in many cases the mesh might have an offset barycenter with respect to the reference that we want to use for the body) This class does automatically, at object creation: More...
 
class  ChBodyEasySphere
 Easy-to-use class for quick creation of rigid bodies with a spherical shape. More...
 
class  ChBodyFrame
 Class for objects that represent moving frames in space and contain state variables. More...
 
class  ChBoundary
 Utility class for specifying a collision boundary composed of multiple semi-planes. More...
 
class  ChBoxShape
 Class for a box shape that can be visualized in some way. More...
 
class  ChCamera
 Class for defining a videocamera point of view with basic settings. More...
 
class  ChCapsuleShape
 Class for referencing a capsule shape that can be visualized in some way. 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  ChColor
 Class for setting a color (used by ChVisualization) More...
 
class  ChColorAsset
 Base class for assets that carry basic informations about the surface color for visualization assets. More...
 
class  ChCommDistributed
 This class holds functions for processing the system's bodies to determine when a body needs to be sent to another rank for either an update or for creation of a ghost. More...
 
class  ChConeShape
 Class for referencing a cone shape that can be visualized in some way. More...
 
class  ChConstantDistribution
 Class for a distribution with a single 'value' that has probability 1.0 (that is, the distribution has a spike corresponding to 'value' and zero elsewhere). More...
 
class  ChConstraint
 Base class for representing constraints to be used with variational inequality solvers, used with Linear/CCP/LCP problems including inequalities, equalities, nonlinearities, etc. More...
 
class  ChConstraintBilateral
 Bilateral (joint) constraints. More...
 
class  ChConstraintNgeneric
 This class implements the functionality for a constraint between N objects of type ChVariables(), and defines three constraint matrices, whose column number automatically matches the number of elements in variables vectors. More...
 
class  ChConstraintRigidRigid
 Unilateral (contact) constraints. More...
 
class  ChConstraintThree
 This class is inherited by the base ChConstraint(), which does almost nothing. More...
 
class  ChConstraintThreeBBShaft
 A class for representing a constraint between two bodies (2x6dof in space) and a 1D dof (a shaft) More...
 
class  ChConstraintThreeGeneric
 This class is inherited by the base ChConstraintThree(), which is a base for triple constraints. 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
 This class implements the functionality for a constraint between a couple of 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
 This class is inherited from the ChConstraintTwoTuples, It is used to represent the normal reaction between two objects, each represented by a tuple of ChVariables objects, ONLY when also two ChConstraintTwoTuplesFrictionT objects are used to represent friction. 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
 This class is inherited from ChConstraintTwoTuples, It is used to represent the normal reaction between two objects, each represented by a tuple of ChVariables objects, ONLY when also two ChConstraintTwoTuplesFrictionT objects are used to represent friction. 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 One should inherit from ChContactable_1vars, ChContactable_2vars etc. 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  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  ChContinuumSPH
 Class for SPH fluid material, with basic property of incompressible fluid. More...
 
class  ChControllerPID
 Class for a basic PID controller. More...
 
class  ChConveyor
 Class for conveyor belt. More...
 
class  ChCoordsys
 COORDSYS: More...
 
class  ChCubicSpline
 Implementation of 1-D piece-wise cubic spline curves. More...
 
class  ChCylinderShape
 Class for referencing a cylinder shape that can be visualized in some way. More...
 
class  ChDirectSolverLS
 Base class for sparse direct linear solvers. More...
 
class  ChDiscreteDistribution
 Class that can be used to generate sample numbers according to a discrete probability distribution. More...
 
class  ChDistributedDataManager
 A class for storing data for maintaining a consistent view of a distributed simulation consisting of multiple wrapped instances of ChSystemMulticoreSMC. More...
 
class  ChDistribution
 Base class for all random distributions. More...
 
class  ChDomainDistributed
 This class maps sub-domains of the global simulation domain to each MPI rank. More...
 
class  ChEllipsoidShape
 Class for referencing an ellipsoid shape that can be visualized in some way. More...
 
class  ChEmitterAsset
 Class that attaches a ChParticleEmitter to a physics item (most often that item is a ChBody). More...
 
class  ChEnumMapperBase
 Class for mapping enums to ChNameValue pairs that contain a 'readable' ascii string of the selected enum. More...
 
class  ChException
 Class for exceptions for throw() catch() mechanism. More...
 
class  ChExceptionArchive
 Macro to create a ChDetect_ArchiveINconstructor that can be used in templates, to select which specialized template to use. More...
 
class  ChFEAContainer
 Container of FEA nodes. More...
 
class  ChFile_ps
 Class for postScript(TM) output. More...
 
class  ChFile_ps_axis_setting
 Class for settings of an axis (x or y, or t) of a 2D plotting of a function on a EPS file. More...
 
class  ChFile_ps_color
 Class for RGB color for a PostScript item (line, circle, etc) More...
 
class  ChFile_ps_graph_setting
 Class for generic settings of a 2D plotting of a function on a EPS file. 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
 ChFrame: a class for coordinate systems in 3D space. More...
 
class  ChFrameMoving
 ChFrameMoving: a class for coordinate systems in 3D space. More...
 
class  ChFseqNode
 Node for the list of functions in a ChFunction_Sequence object. More...
 
class  ChFunction
 Interface base class for scalar functions of the type: y= f(x) More...
 
class  ChFunction_Const
 Constant function: y = C More...
 
class  ChFunction_ConstAcc
 Constant acceleration function: More...
 
class  ChFunction_Derive
 Derivative of a function: y = df/dx More...
 
class  ChFunction_Fillet3
 Cubic fillet function (cubic poly with C0 C1 boundary conditions). More...
 
class  ChFunction_Integrate
 Integral of a function: y = int{ f(x) dx More...
 
class  ChFunction_Lambda
 
class  ChFunction_Matlab
 Matlab function: y = matlab evaluation of function y=f(x) More...
 
class  ChFunction_Mirror
 Mirror function: y = __/\__ Mirrors a function about a vertical axis. More...
 
class  ChFunction_Mocap
 Motion capture (sample) function: y = (linear interpolated array of samples) More...
 
class  ChFunction_Noise
 Noise function: y = multi-octave noise with cubic interpolation. More...
 
class  ChFunction_Operation
 Operation between functions: More...
 
class  ChFunction_Oscilloscope
 Oscilloscope function. More...
 
class  ChFunction_Poly
 POLYNOMIAL FUNCTION: y = a + bx + cx^2 + dx^3 + ... More...
 
class  ChFunction_Poly345
 Ramp function, as a 3-4-5 polynomial: More...
 
class  ChFunction_Ramp
 Linear function (like a straight ramp): y = y0 + x * speed More...
 
class  ChFunction_Recorder
 Recorder function: More...
 
class  ChFunction_Repeat
 Repeat function: y = __/__/__/ More...
 
class  ChFunction_Sequence
 Sequence function: y = sequence_of_functions(f1(y), f2(y), f3(y)) All other function types can be inserted into this. More...
 
class  ChFunction_Setpoint
 Function that returns Y from an externally-provided value, as a ZOH (zero order hold) block. More...
 
class  ChFunction_SetpointCallback
 Interface for functions that uses a callback to return a Y value, as a ZOH (zero order hold) block. More...
 
class  ChFunction_Sigma
 Sigma function: y = polynomial smooth ramp More...
 
class  ChFunction_Sine
 Sine function y = sin (phase + w*x ) where w=2*PI*freq. More...
 
class  ChFunctionPosition
 Interface base class for scalar->vector functions of the type: More...
 
class  ChFunctionPosition_line
 A motion function p=f(s) where p(t) is defined with a ChLine geometry object, ex. More...
 
class  ChFunctionPosition_setpoint
 A motion function p=f(s) where p(t) is an externally-provided sample, as a ZOH (zero order hold) of FOH (first order). More...
 
class  ChFunctionPosition_XYZfunctions
 A motion function p=f(s) where p(t) is defined with three independent ChFunction objects, each for px, py, pz component. More...
 
class  ChFunctionRotation
 Interface base class for scalar->quaternion functions of the type: More...
 
class  ChFunctionRotation_ABCfunctions
 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 (ex. More...
 
class  ChFunctionRotation_axis
 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  ChFunctionRotation_setpoint
 A rotation q=f(s) provided from a rotation sample, continuously updated by the user, behaving as a ZOH (zero order hold) of FOH (first order). More...
 
class  ChFunctionRotation_spline
 A rotation function q=f(s) that interpolates n rotations using a "quaternion spline" of generic order. More...
 
class  ChFunctionRotation_SQUAD
 A rotation function q=f(s) that interpolates n rotations using a SQUAD spherical quadrangle interpolation between quaternions. More...
 
class  ChFunctorArchiveIn
 Functor to call the ArchiveIN function for unrelated classes that implemented them. More...
 
class  ChFx
 Abstract interface class for math functions of the type A=f(B) where A and B are vectors of real values (to the limit, also single scalar values). More...
 
class  ChFxCfunction
 Class for A=f(B) math functions, where the function is defined by wrapping a C function of the 'old' type, i.e. More...
 
class  ChFxCfunctionS
 Class for A=f(B) math functions, where the function is defined by wrapping a C function of the 'old' type, i.e. More...
 
class  ChGenotype
 Class for individuals of the population; for the ChOptimizerGenetic optimization engine. 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  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  ChIntegrable1D
 Base class for 1D integrand T=f(x) to be used in ChQuadrature. More...
 
class  ChIntegrable2D
 As ChIntegrable1D, but for 2D integrand T=f(x,y) to be used in ChQuadrature. More...
 
class  ChIntegrable3D
 As ChIntegrable1D, but for 3D integrand T=f(x,y,z) to be used in ChQuadrature. More...
 
class  ChIntegrableIIorder
 Special subcase: II-order differential system. 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  ChKblock
 Base class for representing items which introduce block-sparse matrices, that is blocks that connect some 'variables' and build a matrix K in a sparse variational inequality VI(Z*x-d,K): More...
 
class  ChKblockGeneric
 Class that represent nxn sparse blocks to put into K global matrix, that is blocks that connect N 'variables' and build a matrix K in a sparse variational inequality VI(Z*x-d,K): More...
 
class  ChLineShape
 Class for referencing a ChLine that can be visualized in some way. More...
 
class  ChLink
 Base class for joints between two ChBodyFrame objects. More...
 
class  ChLinkBase
 Base class for all types of constraints that act like mechanical joints ('links') in 3D space. More...
 
class  ChLinkBrake
 Link representing a brake between two rigid bodies, including the sticking effect. More...
 
class  ChLinkBushing
 ChLinkBushing class. More...
 
class  ChLinkClearance
 A class for the custom fast simulation of revolute joints with clearance. More...
 
class  ChLinkDistance
 Class for enforcing a fixed polar distance between two points on two ChBodyFrame objects. More...
 
class  ChLinkForce
 Class for forces in link joints of type ChLinkLock. More...
 
class  ChLinkGear
 Gear link between two rigid bodies. More...
 
class  ChLinkLimit
 Class for limits in ChLinkLock joints. More...
 
class  ChLinkLinActuator
 Class for linear actuators between two markers, as the actuator were joined with two spherical bearing at the origin of the two markers. More...
 
class  ChLinkLock
 Base class for joints implemented using the "lock formulation". More...
 
class  ChLinkLockAlign
 Align joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockCylindrical
 Cylindrical joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockFree
 Free joint, with the 'ChLinkLock' formulation. 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  ChLinkLockPlanePlane
 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  ChLinkLockPrismatic
 Prismatic joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockRevolute
 Revolute joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockRevolutePrismatic
 RevolutePrismatic joint, with the 'ChLinkLock' formulation. More...
 
class  ChLinkLockSpherical
 Spherical joint, with the 'ChLinkLock' formulation. 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 all 'simple' constraints between two frames attached to two bodies. More...
 
class  ChLinkMateCoaxial
 Mate constraint of coaxial type. More...
 
class  ChLinkMateFix
 Mate constraint that completely fix one frame's rotation and translation respect to the other frame. More...
 
class  ChLinkMateGeneric
 Generic mate constraint, where one can select which DOFs must be constrained between two frames attached to the two bodies. More...
 
class  ChLinkMateOrthogonal
 Mate constraint of orthogonal type. More...
 
class  ChLinkMateParallel
 Mate constraint of parallel type. More...
 
class  ChLinkMatePlane
 Mate constraint of plane-to-plane type. More...
 
class  ChLinkMateSpherical
 Mate constraint of spherical type. More...
 
class  ChLinkMateXdistance
 Mate constraining distance of origin of frame B respect to X axis of frame A. More...
 
class  ChLinkMotionImposed
 A joint that enforces 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
 This is an "interface" from 3D to a powertrain/powertrain that is modeled via 1D elements such as ChShaft, ChShaftsMotor, ChShaftsGearbox, ChShaftsClutch, etc. More...
 
class  ChLinkMotorLinearForce
 A linear motor that applies a force between two frames on two bodies. More...
 
class  ChLinkMotorLinearPosition
 A linear motor that enforces the position x(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
 This is an "interface" from 3D to a powertrain/powertrain that is modeled via 1D elements such as ChShaft, ChShaftsMotor, ChShaftsGearbox, ChShaftsClutch, etc. 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  ChLinkPointSpline
 ChLinkPointSpline class. More...
 
class  ChLinkPulley
 Class to create pulleys on two rigid bodies, connected by a belt. More...
 
class  ChLinkRackpinion
 Rack-pinion link between two body frames. More...
 
class  ChLinkRevolute
 Class for modeling a revolute joint between two two ChBodyFrame objects. More...
 
class  ChLinkRevoluteSpherical
 Class for modeling a composite revolute-spherical joint between two two ChBodyFrame objects. More...
 
class  ChLinkRevoluteTranslational
 Class for modeling a composite revolute-translational joint between two ChBodyFrame objects. More...
 
class  ChLinkRotSpringCB
 Class for rotational spring-damper elements with the torque specified through a callback object. More...
 
class  ChLinkScrew
 Screw joint between two rigid bodies. More...
 
class  ChLinkSpring
 Class for spring-damper systems, acting along the polar distance of two markers. More...
 
class  ChLinkSpringCB
 Class for spring-damper systems with the force specified through a functor object. More...
 
class  ChLinkTrajectory
 ChLinkTrajectory class. More...
 
class  ChLinkTSDA
 Class for translational spring-damper-actuator (TSDA) with the force optionally specified through a functor object (default, linear TSDA). More...
 
class  ChLinkUniversal
 Class for modeling a universal joint between two two ChBodyFrame objects. More...
 
class  ChList
 Class for linked list. More...
 
class  ChLoad
 Class for a 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  ChLoadBodyMesh
 Class for applying loads to a triangle mesh belonging to a ChBody, as a cluster of forces operating on the underlying 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
 Class for loads applied to a single ChLoadable object. More...
 
class  ChLoaderForceOnSurface
 A very simple surface loader: a constant force vector, applied to a point on a u,v surface. More...
 
class  ChLoaderGravity
 A very usual type of volume loader: the constant gravitational load on Y. More...
 
class  ChLoaderPressure
 A very usual type of surface loader: the constant pressure load, a 3D per-area force that is aligned to the surface normal. More...
 
class  ChLoaderU
 Class of loaders for ChLoadableU objects (which support line loads). More...
 
class  ChLoaderUatomic
 Class of loaders for ChLoadableU objects (which support line loads) of atomic type, that is, with a concentrated load in a point Pu. More...
 
class  ChLoaderUdistributed
 Class of loaders for ChLoadableU objects (which support line loads), for loads of distributed type, so these loads will undergo Gauss quadrature to integrate them in the surface. More...
 
class  ChLoaderUV
 Class of loaders for ChLoadableUV objects (which support surface loads). More...
 
class  ChLoaderUVatomic
 Class of loaders for ChLoadableUV objects (which support surface loads) of atomic type, that is, with a concentrated load in a point Pu,Pv. More...
 
class  ChLoaderUVdistributed
 Class of loaders for ChLoadableUV objects (which support surface loads), for loads of distributed type, so these loads will undergo Gauss quadrature to integrate them in the surface. More...
 
class  ChLoaderUVW
 Class of loaders for ChLoadableUVW objects (which support volume loads). More...
 
class  ChLoaderUVWatomic
 Class of loaders for ChLoadableUVW objects (which support volume loads) of atomic type, that is, with a concentrated load in a point Pu,Pv,Pz. More...
 
class  ChLoaderUVWdistributed
 Class of loaders for ChLoadableUVW objects (which support volume loads), for loads of distributed type, so these loads will undergo Gauss quadrature to integrate them in the volume. More...
 
class  ChLoaderXYZnode
 FORCE AT XYZ NODE Loader for a constant force applied at a XYZ node. More...
 
class  ChLoadJacobians
 Utility class for storing jacobian matrices. More...
 
class  ChLoadXYZnode
 Force at XYZ node (ready to use load) More...
 
class  ChLoadXYZnodeBody
 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(), this is enough to have the load working. More...
 
class  ChLoadXYZnodeBodyBushing
 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  ChLoadXYZnodeBodySpring
 Load representing a spring between a ChNodeXYZ and a ChBody, where the anchoring to body can be set via SetApplicationFrameB(). More...
 
class  ChLoadXYZnodeForce
 Base class for loads representing a concentrated force acting on a ChNodeXYZ. More...
 
class  ChLoadXYZnodeForceAbsolute
 Load representing a concentrated force acting on a ChNodeXYZ, as a constant force, or it provides a function to modulate it with time. More...
 
class  ChLoadXYZnodeXYZnode
 Base class for loads representing a concentrated force acting between two ChNodeXYZ. More...
 
class  ChLoadXYZnodeXYZnodeBushing
 Load representing a XYZ bushing between two ChNodeXYZ, with given with spring stiffness as a ChFunction of displacement, for each X,Y,Z direction. More...
 
class  ChLoadXYZnodeXYZnodeSpring
 Load representing a spring between two ChNodeXYZ, with given damping and spring constants, directed as the distance between the two. More...
 
class  ChLog
 Base class for output of errors, messages, warnings, etc. More...
 
class  ChLogConsole
 Specialized class for logging errors in std::cout. More...
 
class  ChMarker
 Markers are auxiliary reference frames which belong to rigid bodies and move together with them. More...
 
class  ChMaterial
 Visualization material properties. More...
 
class  ChMaterialComposite
 Base class for composite material for a contact pair. More...
 
class  ChMaterialCompositeNSC
 Composite NSC material data for a contact pair. More...
 
class  ChMaterialCompositeSMC
 Composite SMC material data for a contact pair. More...
 
class  ChMaterialCompositionStrategy
 Base class for material composition strategy. More...
 
class  ChMaterialSurface
 Base class for specifying material properties for contact force generation. More...
 
class  ChMaterialSurfaceNSC
 Material data for a collision surface for use with non-smooth (complementarity) contact method. More...
 
class  ChMaterialSurfaceSMC
 Material data for a collision surface for use with smooth (penalty) contact method. More...
 
class  ChMatrix33
 Definition of a 3x3 fixed size matrix to represent 3D rotations and inertia tensors. More...
 
class  ChMatterSPH
 Class for clusters of point nodes that can simulate a fluid or an elastic/plastic solid with the Smooth Particle Hydrodynamics (SPH) approach, that is with a 'meshless' FEA approach. More...
 
class  ChMinMaxDistribution
 Class for a distribution with uniform probability between a lower 'min' value and upper 'max' value (that is, the distribution looks like a rectangle) More...
 
class  ChMulticoreDataManager
 Global data manager for Chrono::Multicore. More...
 
class  ChMumpsEngine
 Wrapper class for the MUMPS direct linear solver. More...
 
class  ChNameValue
 This is a base class for name-value pairs. More...
 
class  ChNode
 Node for linked list. More...
 
class  ChNodeBase
 Class for a node, that has some degrees of freedom and that contain a proxy to the solver. More...
 
class  ChNodeSPH
 Class for a single node in the SPH cluster. 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) using the Box�Muller transform. More...
 
class  ChObj
 Base class for items which can be named, deleted, copied. etc. as in the editor of a 3d modeler. More...
 
class  ChObjShapeFile
 Class for referencing a Wavefront/Alias .obj file containing a shape that can be visualized in some way. 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  ChOptimizer
 Base class for multi-variable optimization. More...
 
class  ChOptimizerGenetic
 Class for global optimization with the genetic method (evolutive simulation). More...
 
class  ChOptimizerGradient
 Class for local optimization with the cheap method of gradient and bisection. More...
 
class  ChOptimizerHybrid
 Class for genetic optimization followed by a refinement with the method of gradient, one after the other. More...
 
class  ChOptimizerLocal
 Class for local optimization with the pseudo-Newton method. More...
 
class  ChPardisoProjectEngine
 Wrapper class for the PardisoProject direct linear solver. More...
 
class  ChParticleBase
 Base class for a single particle to be used in ChIndexedParticles containers. More...
 
class  ChParticleContainer
 Container of rigid particles (3 DOF). More...
 
class  ChParticlesClones
 Class for clusters of 'clone' particles, that is many rigid objects with the same shape and mass. More...
 
class  ChPathShape
 Class for referencing a ChLinePath that can be visualized in some way. More...
 
class  ChPhysicsItem
 Base class for items that can contain objects of ChVariables or ChConstraints, such as rigid bodies, mechanical joints, etc. More...
 
class  ChPointPointDrawing
 Base class for visualization of some deformable line shape between two moving points related to the parent ChPhysicsItem. More...
 
class  ChPointPointSegment
 Class to visualize a line segment between two moving points related to the parent ChPhysicsItem. More...
 
class  ChPointPointSpring
 Class to visualize a coil spring between two moving points related to the parent ChPhysicsItem. 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  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  ChProximityContainerMeshless
 Class for container of many proximity pairs for a meshless deformable continuum (necessary for inter-particle material forces), as CPU typical linked list of ChProximityMeshless objects. More...
 
class  ChProximityContainerSPH
 Class for container of many proximity pairs for SPH (Smooth Particle Hydrodynamics and similar meshless force computations), as CPU typical linked list of ChProximitySPH objects. More...
 
class  ChProximityMeshless
 Class for a proximity pair information in a meshless deformable continumm, made with a cluster of particles - that is, an 'edge' topological connectivity in in a meshless FEA approach, similar to the Smoothed Particle Hydrodynamics. More...
 
class  ChProximitySPH
 Class for a proximity pair information in a SPH cluster of particles - that is, an 'edge' topological connectivity in in a meshless FEA approach, like the Smoothed Particle Hydrodynamics. More...
 
class  ChPythonEngine
 Class for a Python parser. More...
 
class  ChQuadrature
 Class to perform Gauss-Legendre quadrature, in 1D, 2D, 3D. More...
 
class  ChQuadratureTables
 Class to store polynomial roots and weights for the Gauss-Legendre quadrature. More...
 
class  ChQuadratureTablesTetrahedron
 Class to store polynomial roots and weights for quadrature over a tetrahedron. More...
 
class  ChQuadratureTablesTriangle
 Class to store polynomial roots and weights for quadrature over a triangle. More...
 
class  ChQuaternion
 Class defining quaternion objects, that is four-dimensional numbers, also known as Euler parameters. More...
 
class  ChRealtimeStepTimer
 Class for a timer which attempts to enforce soft real-time. More...
 
class  ChRoundedBoxShape
 Class for referencing a rounded box shape that can be visualized in some way. More...
 
class  ChRoundedConeShape
 Class for referencing a rounded cone shape that can be visualized in some way. More...
 
class  ChRoundedCylinderShape
 Class for referencing a rounded cylinder shape that can be visualized in some way. More...
 
class  ChShaft
 Class for one-degree-of-freedom mechanical parts with associated inertia (mass, or J moment of inertial for rotating parts). More...
 
class  ChShaftsBody
 Class for creating a constraint between a 3D ChBody object and a 1D ChShaft object. More...
 
class  ChShaftsBodyTranslation
 Class for creating a constraint between a 3D ChBody object and a 1D ChShaft object that represents a 1D translational DOF (differently from the ChShaftsBody constraint that connects to a rotational DOF) A translation axis must be specified (to tell along which direction the 1D shaft inertia rotation affects the body). More...
 
class  ChShaftsClutch
 Class for defining a clutch or a brake (1D model) between two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsCouple
 Base class for defining constraints between a couple of two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsElasticGear
 Class for defining a torsional spring-damper between two 1D parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsGear
 Class for defining a 'transmission ratio' (a 1D gear) between two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains. 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; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsMotor
 Class for a multipurpose motor (a 1D model of 'imposed torque' or 'imposed velocity' or 'imposed rotation') between two one-degree-of-freedom parts, that is, shafts that can be used to build 1D models of power trains. More...
 
class  ChShaftsMotorAngle
 A motor that enforces the rotation angle r(t) between two ChShaft shafts, using a rheonomic constraint. More...
 
class  ChShaftsMotorBase
 Base class for all "motors" between two 1D elements of ChShaft class. More...
 
class  ChShaftsMotorSpeed
 A motor that enforces the angular speed w(t) between two ChShaft shafts, using a rheonomic constraint. More...
 
class  ChShaftsMotorTorque
 A motor that applies a torque between two ChShaft shafts, a bit like the simplier ChShaftsTorque, with some differences, ex. More...
 
class  ChShaftsPlanetary
 Class for defining a planetary gear between three one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains; this is more efficient than simulating power trains modeled full 3D ChBody objects). More...
 
class  ChShaftsThermalEngine
 Class for defining a thermal engine between two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of power trains. More...
 
class  ChShaftsTorque
 Class for defining a user-defined torque between two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsTorqueBase
 Base class for all stuff defining a torque between two one-degree-of-freedom parts, for example torsional dampers, torsional springs, electric engines, etc. More...
 
class  ChShaftsTorqueConverter
 Class for defining a torque converter between two one-degree-of-freedom parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsTorsionSpring
 Class for defining a torsional spring-damper between two 1D parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChShaftsTorsionSpringDamper
 Class for defining a torsional spring-damper between two 1D parts; i.e., shafts that can be used to build 1D models of powertrains. More...
 
class  ChSharedMassBody
 Used by ChVariablesBodySharedMass objects to reference a single mass property. More...
 
class  ChShurProduct
 Functor class for calculating the Shur product of the matrix of unilateral constraints. More...
 
class  ChShurProductBilateral
 Functor class for performing the Shur product of the matrix of bilateral constraints. More...
 
class  ChShurProductFEM
 Functor class for performing the Shur product. 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  ChSolverGMRES
 GMRES iterative solver. More...
 
class  ChSolverLS
 Base class for solvers aimed at solving linear systems. 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  ChSolverPardisoProject
 Interface to the Pardiso Project 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  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  ChSphereShape
 Class for referencing a sphere shape that can be visualized in some way. 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  ChStrainTensor
 Class for strain tensors, in compact Voight notation that is with 6 components in a column. More...
 
class  ChStream
 This is a base class for input/output (streaming) More...
 
class  ChStreamFile
 This is a base class for typical output on system's file, on a disk, using the typical C++ 'fstream' handler. More...
 
class  ChStreamIn
 This is a base class for all INPUT streams. More...
 
class  ChStreamInAscii
 This is a base class for all ASCII INPUT streams, in the sense that number are formatted into readable strings, etc. More...
 
class  ChStreamInAsciiFile
 This is a specialized class for ASCII input on system's file,. More...
 
class  ChStreamInAsciiVector
 This is a specialized class for ASCII input from wrapped std::vector<char>,. More...
 
class  ChStreamInBinary
 This is a base class for all BINARY INPUT streams, in a way such that the stream is platform independent (see the 'little endian' stuff in 'floating point to persistent data' topics..) Defines some << operators from basic types, converting all them into calls to the Output() function. More...
 
class  ChStreamInBinaryFile
 This is a specialized class for BINARY input on system's file,. More...
 
class  ChStreamInBinaryStream
 This is a specialized class for BINARY input from wrapped std::istream,. More...
 
class  ChStreamInBinaryVector
 This is a specialized class for BINARY input from wrapped std::vector<char>,. More...
 
class  ChStreamIstreamWrapper
 This is a wrapper for already-opened std::istream input streams. More...
 
class  ChStreamOstreamWrapper
 This is a wrapper for already-opened std::ostream output streams (like std::cout or similar) More...
 
class  ChStreamOut
 This is a base class for all OUTPUT streams. More...
 
class  ChStreamOutAscii
 This is a base class for all ASCII OUTPUT streams, in the sense that number are formatted into readable strings, etc. More...
 
class  ChStreamOutAsciiFile
 This is a specialized class for ASCII output on system's file,. More...
 
class  ChStreamOutAsciiVector
 This is a specialized class for ASCII output to wrapped std::vector<char>,. More...
 
class  ChStreamOutBinary
 This is a base class for all BINARY OUTPUT streams, in a way such that the stream is platform independent (see the 'little endian' stuff in 'floating point to persistent data' topics..) Defines some << operators from basic types, converting all them into calls to the Output() function. More...
 
class  ChStreamOutBinaryFile
 This is a specialized class for BINARY output on system's file,. More...
 
class  ChStreamOutBinaryStream
 This is a specialized class for BINARY output to wrapped std::ostream,. More...
 
class  ChStreamOutBinaryVector
 This is a specialized class for BINARY output to wrapped std::vector<char>,. More...
 
class  ChStreamVectorWrapper
 This is a wrapper for a std::vector<char> (buffer of chars) More...
 
class  ChStressTensor
 Class for stress tensors, in compact Voight notation that is with 6 components in a column. More...
 
class  ChSurfaceShape
 Class for referencing a ChSurface u,v, parametric surface that can be visualized in some way. More...
 
class  ChSystem
 Physical system. More...
 
class  ChSystemDescriptor
 Base class for collecting objects inherited from ChConstraint, ChVariables and optionally ChKblock. More...
 
class  ChSystemDescriptorMulticore
 System descriptor for Chrono::Multicore. More...
 
class  ChSystemDistributed
 This is the main user interface for Chrono::Distributed Add bodies and set all settings through the system. 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
 Base class for assets that define basic textures. More...
 
class  ChTimer
 Class for high-resolution timing. 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  ChTransform
 ChTransform: a class for fast coordinate transformations in 3D space. More...
 
class  ChTriangleMeshShape
 Class for referencing a triangle mesh shape that can be visualized in some way. More...
 
class  ChValue
 Class that handle C++ values of generic type using type erasure and functors. More...
 
class  ChVariables
 Base class for representing objects that introduce 'variables' (also referred as 'v') and their associated mass submatrices for a sparse representation of the problem. More...
 
class  ChVariablesBody
 Specialized class for representing a 6-DOF item for a system, that is a 3D rigid body, with mass matrix and associate variables (a 6 element vector, ex.speed) This is an abstract class, specialized for example in ChVariablesBodyOwnMass and ChVariablesBodySharedMass. More...
 
class  ChVariablesBodyOwnMass
 Specialized class for representing a 6-DOF item for a system, that is a 3D rigid body, with mass matrix and associate variables (a 6 element vector, ex.speed) Differently from the 'naive' implementation ChVariablesGeneric, here a full 6x6 mass matrix is not built, since only the 3x3 inertia matrix and the mass value are enough. More...
 
class  ChVariablesBodySharedMass
 Specialized class for representing a 6-DOF item for a system, that is a 3D rigid body, with mass matrix and associate variables (a 6 element vector, ex.speed) Differently from the 'naive' implementation ChVariablesGeneric, here a full 6x6 mass matrix is not built, since only the 3x3 inertia matrix and the mass value are enough. 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  ChVector
 Definition of general purpose 3d vector variables, such as points in 3D. More...
 
class  ChVector2
 Definition of a general purpose 2d vector. More...
 
class  ChVisualization
 Base class for assets that define something about visualization (rendering, post processing, etc.) It contains basic information about position, color, and visibility. More...
 
class  ChVisualMaterial
 Class for setting a color (used by ChVisualization) More...
 
class  ChVoightTensor
 Base class for stress and strain tensors, in compact Voight notation that is with 6 components in a column. More...
 
class  ChWeibullDistribution
 Class that generates the Weibull distribution. 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...
 
struct  host_container
 Structure of arrays containing simulation data. More...
 
struct  LocalShapeNode
 Linked-list node for tracking free shapes. 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
 Structure of data for sending a collision shape to a rank. More...
 
struct  shape_container
 Structure of arrays containing contact shape information. More...
 
class  solver_measures
 Solver measures. More...
 
class  solver_settings
 Chrono::Multicore solver_settings. More...
 
struct  TimerData
 Wrapper class for a timer object. More...
 

Typedefs

typedef ChCoordsys< double > Coordsys
 Shortcut for faster use of typical double-precision coordsys. More...
 
typedef ChCoordsys< float > CoordsysF
 Shortcut for faster use of typical single-precision coordsys.
 
template<typename T = double>
using ChMatrixDynamic = Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
 Dense matrix with dynamic size (i.e., with size a run-time variable, unknown at compile time). 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). More...
 
template<typename T = double>
using ChVectorDynamic = Eigen::Matrix< T, Eigen::Dynamic, 1, Eigen::ColMajor >
 Column vector with dynamic size (i.e., with size a run-time variable, 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 a run-time variable, 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...
 
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 ChArray = Eigen::Array< T, Eigen::Dynamic, 1, Eigen::ColMajor >
 General-purpose column array with dynamic size. More...
 
using ChSparseMatrix = Eigen::SparseMatrix< double, Eigen::RowMajor, int >
 Sparse matrix representation. More...
 
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 > Quaternion
 Shortcut for faster use of typical double-precision quaternion. More...
 
typedef ChQuaternion< float > QuaternionF
 Shortcut for faster use of typical single-precision quaternion. More...
 
typedef ChVector< double > Vector
 Shortcut for faster use of typical double-precision vectors. More...
 
typedef ChVector< float > VectorF
 Shortcut for faster use of typical single-precision vectors. More...
 
typedef void(* ChThreadFunc) (void *userPtr, void *lsMemory)
 
typedef void *(* ChMemorySetupFunc) ()
 
typedef unsigned int uint32_t
 
typedef ChThreadsPOSIX ChThreadsPlatformImplementation
 
typedef struct chrono::BodyExchange BodyExchange
 Structure of data for sending a new body to a rank.
 
typedef struct chrono::BodyUpdate BodyUpdate
 Structure of data for sending an update of an existing body to a rank.
 
typedef struct chrono::Shape Shape
 Structure of data for sending a collision shape to a rank. More...
 
typedef double real
 

Enumerations

enum  AngleSet {
  ANGLE_AXIS, AngleSet::EULERO, AngleSet::CARDANO, AngleSet::HPB,
  AngleSet::RXYZ, RODRIGUEZ, QUATERNION
}
 Definitions of various angle sets for conversions. More...
 
enum  ChContactMethod { ChContactMethod::NSC, ChContactMethod::SMC }
 Enumeration of contact methods. More...
 
enum  eChConstraintMode { CONSTRAINT_FREE = 0, CONSTRAINT_LOCK = 1, CONSTRAINT_UNILATERAL = 2, CONSTRAINT_FRIC = 3 }
 Modes for constraint. More...
 
enum  eChUpdateFlags : unsigned int { eChUpdateFlags::ALL = 0x0, eChUpdateFlags::NEW_STEP = 0x1, eChUpdateFlags::NO_ASSETS = 0x2, eChUpdateFlags::NO_COLLISION_SHAPES = 0x4 }
 Flags to be passed to objects being updated during time stepping. More...
 
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  CollisionSystemType { CollisionSystemType::COLLSYS_MULTICORE, CollisionSystemType::COLLSYS_BULLET_MULTICORE }
 Enumeration for the collision system type. More...
 
enum  NarrowPhaseType { NarrowPhaseType::NARROWPHASE_MPR, NarrowPhaseType::NARROWPHASE_R, NarrowPhaseType::NARROWPHASE_HYBRID_MPR }
 Enumeration of narrow-phase collision methods. 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

void * aligned_malloc (size_t size, size_t alignment)
 
void aligned_free (void *ptr)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E >::type operator| (E lhs, E rhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E >::type operator& (E lhs, E rhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E >::type operator^ (E lhs, E rhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E >::type operator~ (E lhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E & >::type operator|= (E &lhs, E rhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E & >::type operator&= (E &lhs, E rhs)
 
template<typename E >
std::enable_if< enable_bitmask_operators< E >::enable, E & >::type operator^= (E &lhs, E rhs)
 
const ChApi ChCoordsys< double > CSYSNULL (VNULL, QNULL)
 
const ChApi ChCoordsys< double > CSYSNORM (VNULL, QUNIT)
 
Coordsys Force2Dcsys (const Coordsys &cs)
 Force 3d coordsys to lie on a XY plane (note: no normaliz. on quat)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChCoordsys< Real > &cs)
 Insertion of coordsys to output stream.
 
template<class Real >
ChVector< Real > operator* (const ChCoordsys< Real > &Fa, const ChVector< 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 ChVector< 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 >
ChVector< Real > operator>> (const ChVector< 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 ChVector< 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...
 
ChVector2 pv_set (double x, double y)
 
ChVector2 pv_set (ChVector<> mv)
 
template<class Real >
ChCoordsys< Real > operator* (const ChFrame< Real > &Fa, const ChCoordsys< 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 ChCoordsys Returns a ChCoordsys. More...
 
template<class Real >
ChFrame< Real > operator* (const ChCoordsys< 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 ChCoordsys frame_B is a ChFrame Returns a ChFrame. More...
 
template<class Real >
ChCoordsys< Real > operator>> (const ChCoordsys< 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 ChCoordsys frame_B is a ChFrame Returns a ChCoordsys. More...
 
template<class Real >
ChFrame< Real > operator>> (const ChFrame< Real > &Fa, const ChCoordsys< 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 ChCoordsys Returns a ChFrame. More...
 
template<class Real >
ChVector< Real > operator* (const ChFrame< Real > &Fa, const ChVector< Real > &Fb)
 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 ChVector< Real > &Fa, 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 >
ChVector< Real > operator>> (const ChVector< Real > &Fa, 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 ChVector< Real > &Fb)
 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 > &Fb)
 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 > &Fa, 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 > &Fa, 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 > &Fb)
 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 > &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 ChCoordsys frame_B is a ChFrameMoving Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator>> (const ChFrameMoving< Real > &Fa, const ChCoordsys< 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 ChCoordsys Returns a ChFrameMoving. More...
 
template<class Real >
ChFrameMoving< Real > operator* (const ChVector< Real > &Fa, 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 ChVector< Real > &Fb)
 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 > &Fa, 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 > &Fb)
 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 SetFirstIntID (int val)
 Set the start value for the sequence of IDs (ATTENTION: not thread safe) Subsequent calls to GetUniqueIntID() will return val+1, val+2, etc. 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)
 Obtain the complete 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.
 
ChApi int GetUniqueIntID ()
 Obtain a unique identifier (thread-safe)
 
ChLogGetLog ()
 Global function to get the current ChLog object.
 
void SetLog (ChLog &new_logobject)
 Global function to set another ChLog object as current 'global' logging system. More...
 
void SetLogDefault ()
 Global function to set the default ChLogConsole output to std::output.
 
double ChAtan2 (double mcos, double msin)
 Computes the atan2, returning angle given cosine and sine.
 
void ChSetRandomSeed (long newseed)
 Sets the seed of the ChRandom function (Park-Miller method)
 
double ChRandom ()
 Returns random value in (0..1) interval with Park-Miller method.
 
void ChPeriodicPar (double &u, int closed)
 Parameter make periodic in 0..1 (using 0..1 modulus if closed, otherwise clamping in 0..1 range)
 
double ChNoise (double x, double amp, double freq, int octaves, double amp_ratio)
 Computes a 1D harmonic multi-octave noise.
 
double ChSineStep (double x, double x1, double y1, double x2, double y2)
 Smooth (sinusoidal) ramp between y1 and y2. More...
 
int ChMax (int a, int b)
 Maximum between two values.
 
double ChMax (double a, double b)
 Maximum between two values.
 
int ChMin (int a, int b)
 Minimum between two values.
 
double ChMin (double a, double b)
 Minimum between two values.
 
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.
 
void StreamOUTdenseMatlabFormat (ChMatrixConstRef A, ChStreamOutAscii &stream)
 Serialization of a dense matrix or vector into an ASCII stream (e.g. a file) in Matlab format.
 
void PasteMatrix (ChSparseMatrix &matrTo, ChMatrixConstRef matrFrom, int insrow, int inscol, bool overwrite=true)
 Paste a given matrix into a sparse matrix at position (insrow, inscol). More...
 
void StreamOUTsparseMatlabFormat (ChSparseMatrix &matr, ChStreamOutAscii &mstream)
 Serialization of a sparse matrix to an ASCI stream (e.g., a file) in Matlab sparse matrix format. More...
 
void StreamOUT (ChSparseMatrix &matr, ChStreamOutAscii &stream)
 Serialization of a sparse matrix to an ASCII stream (for debugging; only the top-left 8x8 corner is printed).
 
template<typename Real >
ChVector< Real > operator* (const Eigen::Transpose< Eigen::Matrix< Real, 3, 3, Eigen::RowMajor >> &A, const ChVector< Real > &v)
 Multiply a transposed 3x3 matrix with a vector.
 
template<typename Real >
ChVector< Real > operator* (const Eigen::Transpose< const Eigen::Matrix< Real, 3, 3, Eigen::RowMajor >> &A, const ChVector< Real > &v)
 Multiply a transposed const 3x3 matrix with a vector.
 
template<class Real >
ChMatrix33< Real > TensorProduct (const ChVector< Real > &vA, const ChVector< Real > &vB)
 Return the outer product (a 3x3 matrix) of two vectors.
 
template<typename T , typename U >
ChVector< 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 ChVector< 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 ChVector< 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 ChApi ChQuaternion< double > QNULL (0., 0., 0., 0.)
 
const ChApi ChQuaternion< double > QUNIT (1., 0., 0., 0.)
 
const ChApi ChQuaternion< double > Q_ROTATE_Y_TO_X (CH_C_SQRT_1_2, 0, 0, -CH_C_SQRT_1_2)
 
const ChApi ChQuaternion< double > Q_ROTATE_Y_TO_Z (CH_C_SQRT_1_2, CH_C_SQRT_1_2, 0, 0)
 
const ChApi ChQuaternion< double > Q_ROTATE_X_TO_Y (CH_C_SQRT_1_2, 0, 0, CH_C_SQRT_1_2)
 
const ChApi ChQuaternion< double > Q_ROTATE_X_TO_Z (CH_C_SQRT_1_2, 0, -CH_C_SQRT_1_2, 0)
 
const ChApi ChQuaternion< double > Q_ROTATE_Z_TO_Y (CH_C_SQRT_1_2,-CH_C_SQRT_1_2, 0, 0)
 
const ChApi ChQuaternion< double > Q_ROTATE_Z_TO_X (CH_C_SQRT_1_2, 0, CH_C_SQRT_1_2, 0)
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_X (0., 1., 0., 0.)
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_Y (0., 0., 1., 0.)
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_Z (0., 0., 0., 1.)
 
double Qlength (const ChQuaternion< double > &q)
 
ChQuaternion< double > Qscale (const ChQuaternion< double > &q, double fact)
 
ChQuaternion< double > Qadd (const ChQuaternion< double > &qa, const ChQuaternion< double > &qb)
 
ChQuaternion< double > Qsub (const ChQuaternion< double > &qa, const ChQuaternion< double > &qb)
 
ChQuaternion< double > Qnorm (const ChQuaternion< double > &q)
 Return the norm two of the quaternion. Euler's parameters have norm = 1.
 
ChQuaternion< double > Qconjugate (const ChQuaternion< double > &q)
 Return the conjugate of the quaternion [s,v1,v2,v3] is [s,-v1,-v2,-v3].
 
ChQuaternion< double > Qcross (const ChQuaternion< double > &qa, const ChQuaternion< double > &qb)
 Return the product of two quaternions. It is non-commutative (like cross product in vectors).
 
ChQuaternion< double > Q_from_AngAxis (double angle, const ChVector< double > &axis)
 Get the quaternion from an angle of rotation and an axis, defined in abs coords. More...
 
ChQuaternion< double > Q_from_Vect_to_Vect (const ChVector< double > &fr_vect, const ChVector< double > &to_vect)
 Get the quaternion from a source vector and a destination vector which specifies the rotation from one to the other. More...
 
ChQuaternion< double > Q_from_AngZ (double angleZ)
 
ChQuaternion< double > Q_from_AngX (double angleX)
 
ChQuaternion< double > Q_from_AngY (double angleY)
 
ChQuaternion< double > Q_from_NasaAngles (const ChVector< double > &mang)
 
ChVector< double > Q_to_NasaAngles (const ChQuaternion< double > &q1)
 
ChQuaternion< double > Q_from_Euler123 (const ChVector< double > &ang)
 
ChVector< double > Q_to_Euler123 (const ChQuaternion< double > &mq)
 
void Q_to_AngAxis (const ChQuaternion< double > &quat, double &angle, ChVector< double > &axis)
 
ChQuaternion< double > Qdt_from_Wabs (const ChVector< double > &w, const Quaternion &q)
 Get the quaternion time derivative from the vector of angular speed, with w specified in absolute coords.
 
ChQuaternion< double > Qdt_from_Wrel (const ChVector< double > &w, const Quaternion &q)
 Get the quaternion time derivative from the vector of angular speed, with w specified in local coords.
 
ChQuaternion< double > Qdtdt_from_Aabs (const ChVector< double > &a, const ChQuaternion< double > &q, const ChQuaternion< double > &q_dt)
 Get the quaternion first derivative from the vector of angular acceleration with a specified in absolute coords.
 
ChQuaternion< double > Qdtdt_from_Arel (const ChVector< double > &a, const ChQuaternion< double > &q, const ChQuaternion< double > &q_dt)
 Get the quaternion second derivative from the vector of angular acceleration with a specified in relative coords.
 
ChQuaternion< double > Qdt_from_AngAxis (const ChQuaternion< double > &quat, double angle_dt, const ChVector< double > &axis)
 Get the time derivative from a quaternion, a speed of rotation and an axis, defined in abs coords.
 
ChQuaternion< double > Qdtdt_from_AngAxis (double angle_dtdt, const ChVector< double > &axis, const ChQuaternion< double > &q, const ChQuaternion< double > &q_dt)
 Get the second time derivative from a quaternion, an angular acceleration and an axis, defined in abs coords.
 
bool Qequal (const ChQuaternion< double > &qa, const ChQuaternion< double > &qb)
 Check if two quaternions are equal.
 
bool Qnotnull (const ChQuaternion< double > &qa)
 Check if quaternion is not null.
 
ChQuaternion< double > ImmQ_complete (const ChVector< double > &qimm)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChQuaternion< double > ImmQ_dt_complete (const ChQuaternion< double > &mq, const ChVector< double > &qimm_dt)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion time derivative, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChQuaternion< double > ImmQ_dtdt_complete (const ChQuaternion< double > &mq, const ChQuaternion< double > &mqdt, const ChVector< double > &qimm_dtdt)
 Given the imaginary (vectorial) {e1 e2 e3} part of a quaternion second time derivative, find the entire quaternion q = {e0, e1, e2, e3}. More...
 
ChQuaternion< double > Angle_to_Quat (AngleSet angset, const ChVector< double > &mangles)
 
ChVector< double > Quat_to_Angle (AngleSet angset, const ChQuaternion< double > &mquat)
 Angle conversion utilities.
 
ChQuaternion< double > AngleDT_to_QuatDT (AngleSet angset, const ChVector< double > &mangles, const ChQuaternion< double > &q)
 
ChQuaternion< double > AngleDTDT_to_QuatDTDT (AngleSet angset, const ChVector< double > &mangles, const ChQuaternion< double > &q)
 
ChVector< double > Angle_to_Angle (AngleSet setfrom, AngleSet setto, const ChVector< double > &mangles)
 
ChVector< double > VaxisXfromQuat (const ChQuaternion< double > &quat)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChQuaternion< Real > &q)
 Insertion of quaternion to output stream.
 
template<class T >
void create (std::string cls_name, T **ppObj)
 Ugly hack added by hammad to get code to compile on osx. More...
 
template<class T >
void StreamSwapBytes (T *ptData)
 Templated function for swapping bytes of objects of type 'T', in general fo whatever T type. More...
 
const ChApi ChVector< double > VNULL (0., 0., 0.)
 
const ChApi ChVector< double > VECT_X (1., 0., 0.)
 
const ChApi ChVector< double > VECT_Y (0., 1., 0.)
 
const ChApi ChVector< double > VECT_Z (0., 0., 1.)
 
template<class RealA , class RealB >
RealA Vdot (const ChVector< RealA > &va, const ChVector< RealB > &vb)
 
template<class RealA >
void Vset (ChVector< RealA > &v, RealA mx, RealA my, RealA mz)
 
template<class RealA , class RealB >
ChVector< RealA > Vadd (const ChVector< RealA > &va, const ChVector< RealB > &vb)
 
template<class RealA , class RealB >
ChVector< RealA > Vsub (const ChVector< RealA > &va, const ChVector< RealB > &vb)
 
template<class RealA , class RealB >
ChVector< RealA > Vcross (const ChVector< RealA > &va, const ChVector< RealB > &vb)
 
template<class RealA , class RealB >
ChVector< RealA > Vmul (const ChVector< RealA > &va, RealB fact)
 
template<class RealA >
RealA Vlength (const ChVector< RealA > &va)
 
template<class RealA >
ChVector< RealA > Vnorm (const ChVector< RealA > &va)
 
template<class RealA , class RealB >
bool Vequal (const ChVector< RealA > &va, const ChVector< RealB > &vb)
 
template<class RealA >
bool Vnotnull (const ChVector< RealA > &va)
 
template<class RealA >
double VangleYZplane (const ChVector< RealA > &va)
 
template<class RealA >
double VangleYZplaneNorm (const ChVector< RealA > &va)
 
template<class RealA >
double VangleRX (const ChVector< RealA > &va)
 
template<class RealA >
ChVector< RealA > VfromPolar (double norm_angle, double pol_angle)
 
template<class RealA >
void XdirToDxDyDz (const ChVector< RealA > &Vxdir, const ChVector< RealA > &Vsingular, ChVector< RealA > &Vx, ChVector< RealA > &Vy, ChVector< RealA > &Vz)
 
template<typename Real >
std::ostream & operator<< (std::ostream &out, const ChVector< Real > &v)
 Insertion ov 3d vector to output stream.
 
template<class Real >
ChVector< Real > operator* (Real s, const ChVector< Real > &V)
 Operator for scaling the vector by a scalar value, as s*V.
 
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<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<typename T >
ChFunction_Lambda< T > make_ChFunction_Lambda (T &&func)
 Create a stack-allocated ChFunction_Lambda. More...
 
template<typename T >
std::shared_ptr< ChFunction_Lambda< T > > make_shared_ChFunction_Lambda (T &&func)
 Create a shared pointer to a heap-allocated ChFunction_Lambda. More...
 
double Interpolate_y (double x, const ChRecPoint &p1, const ChRecPoint &p2)
 
ChQuaternion SLERP (const ChQuaternion<> &qa, const ChQuaternion<> &qb, double t)
 
ChQuaternion QUADRANGLE (const ChQuaternion<> &q0, const ChQuaternion<> &q1, const ChQuaternion<> &q2)
 
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, ChContactContainer *container, Ta *objA, Tb *objB, const collision::ChCollisionInfo &cinfo, const ChMaterialCompositeNSC &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 _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 &mdescriptor)
 
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, ChContactContainer *container, Ta *objA, Tb *objB, const collision::ChCollisionInfo &cinfo, const ChMaterialCompositeSMC &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 &mdescriptor)
 
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 , class Iterator >
ChContainerSearchFromName (const char *m_name, Iterator from, Iterator to)
 
template<class T , class Iterator >
ChContainerSearchFromID (int myID, Iterator from, Iterator to)
 
template<class T >
ChNameValue< T > make_ChNameValue (const char *auto_name, const T &t, const char *custom_name, char flags=0)
 
template<class T >
ChNameValue< T > make_ChNameValue (const char *auto_name, const T &t, char flags=0)
 
template<class T >
ChStreamOutAsciioperator<< (ChStreamOutAscii &mstream, const T &obj)
 This is used to stream out in 'readable' form on a ChStreamOutAscii stream whatever C++ object that implements the archive serialization, i.e. More...
 
 CH_ENUM_MAPPER_BEGIN (eChConstraintMode)
 
 CH_ENUM_VAL (eChConstraintMode::CONSTRAINT_FREE)
 
 CH_ENUM_VAL (eChConstraintMode::CONSTRAINT_FRIC)
 
 CH_ENUM_VAL (eChConstraintMode::CONSTRAINT_LOCK)
 
 CH_ENUM_VAL (eChConstraintMode::CONSTRAINT_UNILATERAL)
 
 CH_ENUM_MAPPER_END (eChConstraintMode)
 
void null_entry_solv_opt (double x[], double g[])
 A 3rd party function which performs local optimization.
 
double CalcFO (double x[], void *idData)
 Ch_local_optimizer Local optimization engine member functions.
 
void showVarFun ()
 
double solvopt (unsigned int n, double x[], double fun(double x[], void *idData), void grad(double x[], double g[]), double options[], void *idData, void(*showDisplay)(), int showEvery, int *breakCicle, int &err_code)
 
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 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...
 
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)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 DotMM (const real *M)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 DotMM (const real *M, const real *N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 MulMM (const real *M, const real *N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 MulM_TM (const real *M, const real *N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 MulMV (const real *M, const real *N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 OuterProductVV (const real *A, const real *B)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 ScaleMat (const real *M, const real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat33 NormalEquations (const real *A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 MAbs (const real *M)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (const Mat33 &M, const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator* (const Mat33 &N, const real scale)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator* (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator+ (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator- (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT real CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT (+, Mat33, Mat33) CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT(-
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT real CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator- (const Mat33 &M)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator* (const real s, const Mat33 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 Abs (const Mat33 &m)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 SkewSymmetric (const real3 &r)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 SkewSymmetricAlt (const real3 &r)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 MultTranspose (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 TransposeMult (const Mat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 Transpose (const Mat33 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Trace (const Mat33 &m)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 OuterProduct (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real InnerProduct (const Mat33 &A, const Mat33 &B)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 Adjoint (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 AdjointTranspose (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Determinant (const Mat33 &m)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 Inverse (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 InverseTranspose (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 InverseUnsafe (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 InverseTransposeUnsafe (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Norm (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real NormSq (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real DoubleDot (const Mat33 &A, const Mat33 &B)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 LargestColumnNormalized (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat33 operator* (const DiagMat33 &M, const Mat33 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (const DiagMat33 &M, const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat33 operator- (const SymMat33 &M, const real &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat33 CofactorMatrix (const SymMat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 LargestColumnNormalized (const SymMat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat33 NormalEquationsMatrix (const Mat33 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (const Mat32 &M, const real2 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API Mat32 operator* (const SymMat33 &M, const Mat32 &N)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat22 operator- (const SymMat22 &M, const real &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat22 CofactorMatrix (const SymMat22 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real2 LargestColumnNormalized (const SymMat22 &A)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat22 TransposeTimesWithSymmetricResult (const Mat32 &A, const Mat32 &B)
 
CUDA_HOST_DEVICE CH_MULTICORE_API SymMat22 ConjugateWithTranspose (const Mat32 &A, const SymMat33 &B)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (const Mat33 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (const Mat32 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (const SymMat33 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (const SymMat22 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void PrintLine (const Mat33 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void PrintLine (const Mat32 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void PrintLine (const SymMat33 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void PrintLine (const SymMat22 &A, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT_PROTO real CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT_PROTO Mat33 CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT_PROTO (+, Mat33, Mat33) CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT_PROTO(-
 
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)
 
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(-
 
CUDA_HOST_DEVICE CH_MULTICORE_API vec3 operator- (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API vec3 operator- (const vec3 &a, const int &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API vec3 operator+ (const vec3 &a, const vec3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API vec3 operator+ (const vec3 &a, const int &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API vec3 Clamp (const vec3 &a, const vec3 &clamp_min, const vec3 &clamp_max)
 
CUDA_HOST_DEVICE real Lerp (const real &start, const real &end, const real &t)
 
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 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 CH_MULTICORE_API real3 Set3 (real x)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Set3 (real x, real y, real z)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator+ (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator- (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator/ (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator+ (const real3 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator- (const real3 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (const real3 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator/ (const real3 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator* (real lhs, const real3 &rhs)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator/ (real lhs, const real3 &rhs)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 operator- (const real3 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (/, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (+, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (-, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (/, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (+, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (-, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Dot (const real3 &v1, const real3 &v2)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Dot (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Normalize (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Length (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Sqrt (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Cross (const real3 &b, const real3 &c)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Abs (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Sign (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Max (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Min (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Max (const real3 &a, const real &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Min (const real3 &a, const real &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Max (const real3 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Min (const real3 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Length2 (const real3 &v1)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real SafeLength (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 SafeNormalize (const real3 &v, const real3 &safe)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Clamp (const real3 &a, const real3 &clamp_min, const real3 &clamp_max)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Clamp (const real3 &v, real max_length)
 
CUDA_HOST_DEVICE CH_MULTICORE_API bool operator< (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API bool operator> (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API bool operator== (const real3 &a, const real3 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Round (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API bool IsZero (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 OrthogonalVector (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 UnitOrthogonalVector (const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (real3 v, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (/, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (+, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (-, real, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (/, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (+, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (-, real3, real3)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Sort (real &a, real &b, real &c)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 Set4 (real x)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 Set4 (real x, real y, real z, real w)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator+ (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator- (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator* (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator/ (const real4 &a, const real4 &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator+ (const real4 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator- (const real4 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator* (const real4 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator/ (const real4 &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 operator- (const real4 &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real4 Dot4 (const real3 &v, const real3 &v1, const real3 &v2, const real3 &v3, const real3 &v4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (/, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (+, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (-, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (/, real4, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (+, real4, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL (-, real4, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion SetQ (real x)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion SetQ (real w, real x, real y, real z)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator+ (const quaternion &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator- (const quaternion &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator* (const quaternion &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator/ (const quaternion &a, real b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator- (const quaternion &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion operator~ (const quaternion &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion Inv (const quaternion &a)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Dot (const quaternion &v1, const quaternion &v2)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real Dot (const quaternion &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion Mult (const quaternion &a, const quaternion &b)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion Normalize (const quaternion &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 Rotate (const real3 &v, const quaternion &q)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 RotateT (const real3 &v, const quaternion &q)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 AbsRotate (const quaternion &q, const real3 &v)
 
CUDA_HOST_DEVICE CH_MULTICORE_API quaternion Q_from_AngAxis (const real &angle, const real3 &axis)
 
CUDA_HOST_DEVICE CH_MULTICORE_API real3 AMatV (const quaternion &q)
 
CUDA_HOST_DEVICE CH_MULTICORE_API void Print (quaternion v, const char *name)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (/, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (+, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (-, real, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (/, real4, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (+, real4, real4)
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_PROTO (-, real4, real4)
 
uvec3 SortedFace (int face, const uvec4 &tetrahedron)
 
uvec3 UnSortedFace (int face, const uvec4 &tetrahedron)
 
bool Cone_generalized_rnode (real &gamma_n, real &gamma_u, real &gamma_v, const real &mu)
 
bool customCompare (const FaceData &face1, const FaceData &face2)
 
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)
 
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)
 
BilateralType GetBilateralType (ChPhysicsItem *item)
 

Variables

const ChApi ChCoordsys< double > CSYSNULL
 
const ChApi ChCoordsys< double > CSYSNORM
 
ChQuadratureTables static_tables (1, CH_QUADRATURE_STATIC_TABLES)
 
ChQuadratureTablesTriangle static_tables_triangle
 
ChQuadratureTablesTetrahedron static_tables_tetrahedron
 
const ChApi ChQuaternion< double > QNULL
 Constant null quaternion: {0, 0, 0, 0}.
 
const ChApi ChQuaternion< double > QUNIT
 Constant unit quaternion: {1, 0, 0, 0} , corresponds to no rotation (diagonal rotation matrix)
 
const ChApi ChQuaternion< double > Q_ROTATE_Y_TO_X
 
const ChApi ChQuaternion< double > Q_ROTATE_Y_TO_Z
 
const ChApi ChQuaternion< double > Q_ROTATE_X_TO_Y
 
const ChApi ChQuaternion< double > Q_ROTATE_X_TO_Z
 
const ChApi ChQuaternion< double > Q_ROTATE_Z_TO_Y
 
const ChApi ChQuaternion< double > Q_ROTATE_Z_TO_X
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_X
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_Y
 
const ChApi ChQuaternion< double > Q_FLIP_AROUND_Z
 
const ChApi ChVector< double > VNULL
 
const ChApi ChVector< double > VECT_X
 
const ChApi ChVector< double > VECT_Y
 
const ChApi ChVector< double > VECT_Z
 
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
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT real CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALSALT Mat33 CUDA_HOST_DEVICE CH_MULTICORE_API Mat33
 
CUDA_HOST_DEVICE OPERATOR_EQUALSALT float CUDA_HOST_DEVICE OPERATOR_EQUALSALT Mat33f CUDA_HOST_DEVICE Mat33f
 
CUDA_HOST_DEVICE OPERATOR_EQUALS_IMPL * real2
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL * real3
 
CUDA_HOST_DEVICE CH_MULTICORE_API OPERATOR_EQUALS_IMPL * real4
 

Typedef Documentation

◆ Coordsys

typedef ChCoordsys<double> chrono::Coordsys

Shortcut for faster use of typical double-precision coordsys.

Instead of writing "ChCoordsys<double> foo;" you can write the shorter version "Coordsys foo;"

◆ Quaternion

Shortcut for faster use of typical double-precision quaternion.

Instead of writing
   ChQuaternion<double> foo;
or
   ChQuaternion<> foo;
you can use the shorter version
   Quaternion foo;

◆ QuaternionF

Shortcut for faster use of typical single-precision quaternion.

Instead of writing
   ChQuaternion<float> foo;
you can use the shorter version
   Quaternion foo;

◆ Vector

typedef ChVector<double> chrono::Vector

Shortcut for faster use of typical double-precision vectors.

Instead of writing
   ChVector<double> foo;
or
   ChVector<> foo;
you can use the shorter version
   Vector foo;

◆ VectorF

typedef ChVector<float> chrono::VectorF

Shortcut for faster use of typical single-precision vectors.

Instead of writing
   ChVector<float> foo;
you can use the shorter version
   Vector foo;

Enumeration Type Documentation

◆ AngleSet

enum chrono::AngleSet
strong

Definitions of various angle sets for conversions.

Enumerator
EULERO 

sequence: Z - X' - Z''

CARDANO 

sequence: Z - X' - Y''

HPB 

sequence:

RXYZ 

sequence: X - Y' - Z''

◆ 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

◆ eChConstraintMode

Modes for constraint.

Enumerator
CONSTRAINT_FREE 

the constraint does not enforce anything

CONSTRAINT_LOCK 

the constraint enforces c_i=0;

CONSTRAINT_UNILATERAL 

the constraint enforces linear complementarity c_i>=0, l_i>=0, l_1*c_i=0;

CONSTRAINT_FRIC 

the constraint is one of three reactions in friction (cone complementarity problem)

◆ eChUpdateFlags

enum chrono::eChUpdateFlags : unsigned int
strong

Flags to be passed to objects being updated during time stepping.

They are useful for optimizing the computations, and other reasons. In fact it happens that not all update functions require the same 'level of completeness' in recomputing the data in the objects, for example a ChTimestepper might require multiple StateScatter() calls before advancing to the next timestep (for instance in a RungeKutta integrator it takes 4 intermediate StateScatter() calls) but during the intermediate calls there is no need of updating, say, all 3D meshes in visual assets. This is the reason for these flags. They are used by ChIntegrable::StateScatter() by ChPhysicsItem::Update(), and in other parts of the code.

Enumerator
ALL 

Update all data.

NEW_STEP 

This is called when updating at the beginning of a time step.

NO_ASSETS 

Avoid updating visual assets, if any.

NO_COLLISION_SHAPES 

Avoid updating collision shapes, if any.

Function Documentation

◆ ChSineStep()

ChApi double chrono::ChSineStep ( double  x,
double  x1,
double  y1,
double  x2,
double  y2 
)

Smooth (sinusoidal) ramp between y1 and y2.

Note: must have x1 < x2 (no check).

◆ create()

template<class T >
void chrono::create ( std::string  cls_name,
T **  ppObj 
)

Ugly hack added by hammad to get code to compile on osx.

Compiler had trouble finding the create function, adding include to ChClassRegister made other things break in ChLog so I couldn't do that....

◆ ImmQ_complete()

ChApi ChQuaternion< double > chrono::ImmQ_complete ( const ChVector< double > &  qimm)

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

Note: singularities are possible.

◆ ImmQ_dt_complete()

ChApi ChQuaternion< double > chrono::ImmQ_dt_complete ( const ChQuaternion< double > &  mq,
const ChVector< double > &  qimm_dt 
)

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.

◆ ImmQ_dtdt_complete()

ChApi ChQuaternion< double > chrono::ImmQ_dtdt_complete ( const ChQuaternion< double > &  mq,
const ChQuaternion< double > &  mqdt,
const ChVector< double > &  qimm_dtdt 
)

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.

◆ operator*() [1/15]

template<class Real >
ChFrame<Real> chrono::operator* ( const ChCoordsys< 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 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 > &  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 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 >
ChVector<Real> chrono::operator* ( const ChCoordsys< Real > &  Fa,
const ChVector< 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 > &  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 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 > &  Fb 
)

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 >
ChVector<Real> chrono::operator* ( const ChFrame< Real > &  Fa,
const ChVector< Real > &  Fb 
)

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 > &  Fa,
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 > &  Fa,
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 ChVector< 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 ChVector< Real > &  Fa,
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 ChVector< Real > &  Fa,
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<<()

template<class T >
ChStreamOutAscii& chrono::operator<< ( ChStreamOutAscii mstream,
const T &  obj 
)

This is used to stream out in 'readable' form on a ChStreamOutAscii stream whatever C++ object that implements the archive serialization, i.e.

objects that have ArchiveOUT implemented. For example: GetLog() << mymatrix;

◆ operator>>() [1/14]

template<class Real >
ChCoordsys<Real> chrono::operator>> ( const ChCoordsys< 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 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 ChVector< 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 > &  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 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 > &  Fb 
)

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 ChVector< Real > &  Fb 
)

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 > &  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 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 > &  Fb 
)

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 ChVector< Real > &  Fb 
)

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 > &  Fa,
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 >
ChVector<Real> chrono::operator>> ( const ChVector< 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 >
ChVector<Real> chrono::operator>> ( const ChVector< Real > &  Fa,
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.

◆ Q_from_AngAxis()

ChApi ChQuaternion< double > chrono::Q_from_AngAxis ( double  angle,
const ChVector< double > &  axis 
)

Get the quaternion from an angle of rotation and an axis, defined in abs coords.

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

◆ Q_from_Vect_to_Vect()

ChApi ChQuaternion< double > chrono::Q_from_Vect_to_Vect ( const ChVector< double > &  fr_vect,
const ChVector< double > &  to_vect 
)

Get the quaternion from a source vector and a destination vector which specifies the rotation from one to the other.

The vectors do not need to be normalized.

◆ SetFirstIntID()

ChApi void chrono::SetFirstIntID ( int  val)

Set the start value for the sequence of IDs (ATTENTION: not thread safe) Subsequent calls to GetUniqueIntID() will return val+1, val+2, etc.

The default initial value is 100000.

◆ SetLog()

ChApi void chrono::SetLog ( ChLog new_logobject)

Global function to set another ChLog object as current 'global' logging system.

For example, a plugin developer may like to see logs on a GUI dialog: if so, he can inherit a specialized ChLog class (overriding the Output() function) and use the SetLog() function to have it available all times. Doing so, in your code you can write, for example:

chrono::GetLog() << "message";

◆ StreamSwapBytes()

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

Templated function for swapping bytes of objects of type 'T', in general fo whatever 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.