Tutorials
Dynamic objects of classes with fixed-size vectorizable Eigen object members
  • Many of the Chrono classes now have members that are fixed-size vectorizable Eigen types. These classes overload their operator new to generate 16-byte-aligned pointers (using an Eigen-provided macro).
  • This takes care of situations where one must dynamically create objects of such classes; for more details, see the Eigen documentation.
  • If you need to create STL containers of such classes, you should use a custom allocator that always allocates aligned memory (such as the Eigen-provided Eigen:aligned_allocator); for more details, see the Eigen documentation.
  • Finally, this requirement for aligned memory allocation has implications on creation of shared pointers. Indeed, std::make_shared uses placement new instead of operator new. To address this issue and preserve encapsulation (as much as possible), Chrono provides custom replacement functions for make_shared, available in the chrono_types namespace. These functions will automatically infer if they can safely fallback on std::make_shared or else create a shared pointer with an alternative mechanism that ensures use of aligned memory.
    As such, user code should always use chrono_types::make_shared as in
    auto my_body = chrono_types::make_shared<ChBody>();

Chrono modules

Other tools

Chrono training materials

Documentation guides

  • Documentation tutorials

    Guidelines on writing technical documentation for Chrono (for developers of new modules/features).

virtual double GetVal(double x) const override
Return the function output for input x.
Definition: ChFunctionSine.cpp:28
const std::vector< std::shared_ptr< ChLinkBase > > & GetLinks() const
Get the list of links.
Definition: ChSystem.h:343
void AddTypicalLights()
Simple shortcut to set two point lights in the scene.
Definition: ChVisualSystemIrrlicht.cpp:341
Interface base class for scalar functions.
Definition: ChFunctionBase.h:31
static std::shared_ptr< ChTriangleMeshConnected > CreateFromWavefrontFile(const std::string &filename, bool load_normals=true, bool load_uv=false)
Create and return a ChTriangleMeshConnected from a Wavefront OBJ file.
Definition: ChTriangleMeshConnected.cpp:257
std::string GetChronoDataFile(const std::string &filename)
Get the full path to the specified filename, given relative to the Chrono data directory (thread safe...
Definition: ChGlobal.cpp:37
ChQuaterniond QuatFromAngleX(double angle)
Convert from a rotation about X axis to a quaternion.
Definition: ChRotation.cpp:188
virtual double GetVolume() const override
Return the volume of this solid.
Definition: ChCylinder.cpp:36
__host__ __device__ Real cube(Real a)
Cube a float value.
Definition: custom_math.h:79
void SetAdaptiveNewtonON(int initial_delay, double growth_tolerance)
Enable the adaptive size in the inner Newton loop.
Definition: ChStaticAnalysis.cpp:792
Eigen::Matrix< T, N, 1 > ChVectorN
Column vector with fixed size (known at compile time).
Definition: ChMatrix.h:122
void Add(std::shared_ptr< ChPhysicsItem > item)
Attach an arbitrary ChPhysicsItem (e.g.
Definition: ChSystem.cpp:196
virtual std::shared_ptr< ChSolver > GetSolver()
Access the solver currently associated with this system.
Definition: ChSystem.h:124
MINimum RESidual method.
virtual void BeginScene() override
Perform any necessary operations at the beginning of each rendering frame.
Definition: ChVisualSystemVSG.h:90
virtual void Render() override
Draw all 3D shapes and GUI elements at the current frame.
Definition: ChVisualSystemIrrlicht.cpp:626
void SetMaxPenetrationRecoverySpeed(double value)
Set the speed limit of exiting from penetration situations (default: 0.6).
Definition: ChSystem.h:115
void SetBasePath(const std::string &mpath)
Set the path where all files (.ini, .pov, .assets etc) will be saved.
Definition: ChPovRay.h:80
Base class for composite material for a contact pair.
Definition: ChContactMaterial.h:140
virtual void SetNumThreads(int num_threads_chrono, int num_threads_collision=0, int num_threads_eigen=0)
Set the number of OpenMP threads used by Chrono itself, Eigen, and the collision detection system.
Definition: ChSystem.cpp:373
void SetStartVal(double y0)
Set the initial value.
Definition: ChFunctionRamp.h:48
Create rigid bodies with a box shape.
Definition: ChBodyEasy.h:153
std::shared_ptr< ChContactContainer > GetContactContainer() const
Access the underlying contact container.
Definition: ChSystem.h:463
virtual double GetDer(double x) const override
Return the first derivative of the function.
Definition: ChFunctionSine.cpp:32
virtual void Initialize() override
Initialize the visualization system.
Definition: ChVisualSystemIrrlicht.cpp:181
ChVector3< Real > TransformPointLocalToParent(const ChVector3< Real > &v) const
Transform a point from the local coordinate system to the parent coordinate system.
Definition: ChCoordsys.h:195
Representation of a transform with translation and rotation.
Definition: ChCoordsys.h:28
bool DoStaticAnalysis(ChStaticAnalysis &analysis)
Perform a generic static analysis.
Definition: ChSystem.cpp:1768
void AddSkyBox(const std::string &texture_dir=GetChronoDataFile("skybox/"))
Add a sky box in a 3D scene.
Definition: ChVisualSystemIrrlicht.cpp:354
Type
Supported run-time visualization systems.
Definition: ChVisualSystem.h:36
static std::shared_ptr< ChVisualMaterial > Default()
Create a default material.
Definition: ChVisualMaterial.cpp:231
ChQuaternion< double > ChQuaterniond
Alias for double-precision quaternions.
Definition: ChQuaternion.h:412
Type
Available types of solvers.
Definition: ChSolver.h:38
Sparse left-looking rank-revealing QR factorization.
void BuildBeam(std::shared_ptr< ChMesh > mesh, std::shared_ptr< ChBeamSectionCable > sect, const int N, const ChVector3d A, const ChVector3d B)
Adds cable FEM elements to the mesh to create a segment beam from point A to point B,...
Definition: ChBuilderBeam.cpp:256
Irrlicht base classes (Chrono extensions).
Definition: ChCascadeIrrMeshTools.h:50
Geometric object representing an arc or a circle in 3D space.
Definition: ChLineArc.h:29
std::shared_ptr< ChTimestepper > GetTimestepper() const
Get the timestepper currently used for time integration.
Definition: ChSystem.h:93
const ChQuaterniond QUNIT(1., 0., 0., 0.)
Constant unit quaternion: {1, 0, 0, 0} , corresponds to no rotation (diagonal rotation matrix)
Definition: ChQuaternion.h:431
void SetTimestepper(std::shared_ptr< ChTimestepper > stepper)
Set the timestepper object to be used for time integration.
Definition: ChSystem.h:90
void ExportScript()
Export the script that will be used by POV to process all the exported data and render the complete a...
Definition: ChPovRay.h:184
void SetFromAngleAxis(Real angle, const ChVector3< Real > &axis)
Set the quaternion from an angle of rotation and an axis, defined in absolute coords.
Definition: ChQuaternion.h:1052
static void SetDefaultEffectiveCurvatureRadius(double eff_radius)
Set the default effective radius of curvature (for SMC contact).
Definition: ChCollisionInfo.cpp:67
void drawCircle(ChVisualSystemIrrlicht *vis, double radius, ChCoordsys<> pos, chrono::ChColor col, int resolution, bool use_Zbuffer)
Draw a circle line in 3D space with given color.
Definition: ChIrrTools.cpp:685
bool PutVariable(ChMatrixConstRef mmatr, std::string varname)
Put a matrix in Matlab environment, specifying its name as variable.
Definition: ChMatlabEngine.cpp:72
__host__ __device__ int min(int a, int b)
Return the minimum of two integer numbers.
Definition: custom_math.h:64
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > ChMatrixDynamic
Dense matrix with dynamic size (i.e., with unknown at compile time) and row-major storage.
Definition: ChMatrix.h:75
A basic triangle mesh: just a list of triangles (no edge connectivity info).
Definition: ChTriangleMeshSoup.h:28
void SetFromAngleX(Real angleX)
Set the quaternion from an angle of rotation about X axis.
Definition: ChQuaternion.h:317
bool DoStaticLinear()
Solve the position of static equilibrium (and the reactions).
Definition: ChSystem.cpp:1790
Class for plotting data with GNUplot.
Definition: ChGnuPlot.h:53
const std::vector< std::shared_ptr< ChBody > > & GetBodies() const
Get the list of bodies.
Definition: ChSystem.h:339
void SetVerbose(bool verbose)
Enable/disable verbose output (default: false)
Definition: ChStaticAnalysis.h:202
Loads acting on a single ChLoadable item.
Definition: ChLoad.h:224
virtual void EndScene() override
End the scene draw at the end of each animation frame.
Definition: ChVisualSystemVSG.h:112
Definition of a 3x3 fixed-size matrix to represent 3D rotations and inertia tensors.
Definition: ChMatrix33.h:31
void SetTemplateFile(const std::string &filename)
Set the filename of the template for the script generation.
Definition: ChPovRay.h:84
virtual ChMatrix33 GetGyration() const override
Return the gyration matrix for this solid.
Definition: ChCylinder.cpp:50
Class for state of time-integrable objects.
Definition: ChState.h:34
void ExportData()
This function is used at each timestep to export data formatted in a way that it can be load with the...
Definition: ChPovRay.cpp:752
virtual bool AddTriangleMesh(const ChTriangleMesh &tm)
Add a triangle mesh soup, by passing an entire ChTriangleMesh object.
Definition: ChConvexDecomposition.cpp:318
virtual void AddLink(std::shared_ptr< ChLinkBase > link)
Attach a link to the underlying assembly.
Definition: ChSystem.cpp:144
void SetCustomPOVcommandsScript(const std::string &text)
Set a string (a text block) of custom POV commands that you can optionally append to the POV script f...
Definition: ChPovRay.h:166
Chrono multicore collision detection system.
virtual int AddCamera(const ChVector3d &pos, ChVector3d targ=VNULL) override
Add a camera to the VSG scene.
Definition: ChVisualSystemVSG.cpp:581
virtual void WriteConvexHullsAsWavefrontObj(std::ostream &mstream)
Save the computed convex hulls as a Wavefront file using the '.obj' fileformat, with each hull as a s...
Definition: ChConvexDecomposition.cpp:439
Namespace with classes for the POSTPROCESS module.
Definition: ChApiPostProcess.h:54
void Remove(std::shared_ptr< ChPhysicsItem > item)
Remove arbitrary ChPhysicsItem that was added to the underlying assembly.
Definition: ChSystem.cpp:220
Representation of a 3D transform.
Definition: ChFrame.h:33
ChQuaterniond QuatFromAngleY(double angle)
Convert from a rotation about Y axis to a quaternion.
Definition: ChRotation.cpp:192
Utility class for creating complex beams using ChElementBeamEuler elements, for example subdivides a ...
Definition: ChBuilderBeam.h:42
Eigen::SparseMatrix< double, Eigen::RowMajor, int > ChSparseMatrix
Sparse matrix representation.
Definition: ChMatrix.h:185
Loaders for ChLoadableUVW objects (which support volume loads), for concentrated loads.
Definition: ChLoaderUVW.h:68
Class for wrapping the HACD convex decomposition code revisited by John Ratcliff.
Definition: ChConvexDecomposition.h:148
void drawPolyline(ChVisualSystemIrrlicht *vis, std::vector< ChVector3d > &points, chrono::ChColor col, bool use_Zbuffer)
Draw a polyline in 3D space, given the array of points.
Definition: ChIrrTools.cpp:673
std::shared_ptr< ChCollisionSystem > GetCollisionSystem() const
Access the underlying collision system.
Definition: ChSystem.h:103
ChFrame< double > ChFramed
Alias for double-precision coordinate frames.
Definition: ChFrame.h:352
static void FromTetGenFile(std::shared_ptr< ChMesh > mesh, const char *filename_node, const char *filename_ele, std::shared_ptr< ChContinuumMaterial > my_material, ChVector3d pos_transform=VNULL, ChMatrix33<> rot_transform=ChMatrix33<>(1))
Load tetrahedrons from .node and .ele files as saved by TetGen.
Definition: ChMeshFileLoader.cpp:39
Namespace with classes for the Irrlicht module.
Definition: ChApiIrr.h:47
Class for a timer which attempts to enforce soft real-time.
Definition: ChRealtimeStep.h:25
Accelerated Projected Gradient Descent.
Projected SOR (Successive Over-Relaxation)
void SetIncrementalSteps(int incr_steps)
Set the number of outer iterations that will increment the external load in stepwise manner.
Definition: ChStaticAnalysis.cpp:788
Class for cosimulation interface.
Definition: ChCosimulation.h:39
void SetGravitationalAcceleration(const ChVector3d &gacc)
Set the gravitational acceleration vector.
Definition: ChSystem.h:148
virtual bool GetConvexHullResult(unsigned int hullIndex, ChTriangleMesh &convextrimesh)
Get the n-th computed convex hull, by filling a ChTriangleMesh object that is passed as a parameter.
Definition: ChConvexDecomposition.cpp:416
Ramp function.
Definition: ChFunctionRamp.h:27
Real Length() const
Compute the euclidean norm of the vector, that is its length or magnitude.
Definition: ChVector3.h:847
void Set(Real x, Real y, Real z)
Set the three values of the vector at once.
Definition: ChVector3.h:755
Nonlinear static analysis where the user can define external load(s) that will be incremented gradual...
Definition: ChStaticAnalysis.h:196
void Spin(double step)
Call this function INSIDE the simulation loop, just ONCE per loop (preferably as the last call in the...
Definition: ChRealtimeStep.h:34
virtual int ComputeConvexDecomposition()
Perform the convex decomposition.
Definition: ChConvexDecomposition.cpp:351
void SetFromAngleY(Real angleY)
Set the quaternion from an angle of rotation about Y axis.
Definition: ChQuaternion.h:320
void SetFromAngleZ(Real angleZ)
Set the quaternion from an angle of rotation about Z axis.
Definition: ChQuaternion.h:323
Geometric object representing a segment in 3D space with two end points.
Definition: ChLineSegment.h:29
void SetNewtonDamping(double damping_factor)
Set damping of the Newton iteration.
Definition: ChStaticAnalysis.cpp:801
virtual void EndScene() override
End the scene draw at the end of each animation frame.
Definition: ChVisualSystemIrrlicht.cpp:616
Definition of a visual color.
Definition: ChColor.h:30
Sine function y = A*sin(2*PI*f + phase)`.
Definition: ChFunctionSine.h:28
virtual void BeginScene() override
Perform any necessary operations at the beginning of each rendering frame.
Definition: ChVisualSystemIrrlicht.cpp:567
virtual bool WriteConvexHullsAsChullsFile(std::ostream &mstream)
Write the convex decomposition to a ".chulls" file, where each hull is a sequence of x y z coords.
Definition: ChConvexDecomposition.cpp:77
Operation between functions:
Definition: ChFunctionOperator.h:29
virtual void Render() override
Draw all 3D shapes and GUI elements at the current frame.
Definition: ChVisualSystemVSG.cpp:929
irr::scene::ILightSceneNode * AddLightWithShadow(const ChVector3d &pos, const ChVector3d &aim, double radius, double near_value, double far_value, double angle, unsigned int resolution=512, ChColor color=ChColor(1, 1, 1), bool directional=false, bool clipborder=true)
Add a point light that cast shadow (using soft shadows/shadow maps) Note that the quality of the shad...
Definition: ChVisualSystemIrrlicht.cpp:408
virtual int AddCamera(const ChVector3d &pos, ChVector3d targ=VNULL) override
Add a camera in an Irrlicht 3D scene.
Definition: ChVisualSystemIrrlicht.cpp:287
const std::string & GetChronoOutputPath()
Obtain the path to the output directory for Chrono demos.
Definition: ChGlobal.cpp:52
void drawGrid(ChVisualSystemIrrlicht *vis, double ustep, double vstep, int nu, int nv, ChCoordsys<> pos, chrono::ChColor col, bool use_Zbuffer)
Draw grids in 3D space with given orientation, color, and spacing.
Definition: ChIrrTools.cpp:782
virtual void RemoveLink(std::shared_ptr< ChLinkBase > link)
Remove a link from this assembly.
Definition: ChSystem.cpp:173
ChMatrix33< Real > & GetRotMat()
Return the current rotation as a 3x3 matrix.
Definition: ChFrame.h:155
bool DoStaticNonlinear(int nsteps=10, bool verbose=false)
Solve the position of static equilibrium (and the reactions).
Definition: ChSystem.cpp:1850
Real & x()
Access to components.
Definition: ChVector3.h:49
Function returnin a constant value.
Definition: ChFunctionConst.h:26
virtual void Reset(void)
Reset the input mesh data.
Definition: ChConvexDecomposition.cpp:297
void SetMaxIterationsNewton(int max_newton_iters)
Set the max number of inner iterations for the Newton Raphson procedure (default: 5),...
Definition: ChStaticAnalysis.cpp:784
bool PutSparseMatrix(const ChSparseMatrix &mmatr, std::string varname)
Put a sparse matrix in Matlab environment, specifying its name as variable.
Definition: ChMatlabEngine.cpp:86
void AddUserEventReceiver(irr::IEventReceiver *receiver)
Attach a custom event receiver to the application.
Definition: ChVisualSystemIrrlicht.cpp:435
static void SetDefaultSuggestedMargin(double margin)
Set the default margin (inward penetration).
Definition: ChCollisionModel.cpp:85
Chrono Simulation System.
Definition: ChSystem.h:64
void SetSolverType(ChSolver::Type type)
Choose the solver type, to be used for the simultaneous solution of the constraints in dynamical simu...
Definition: ChSystem.cpp:249
int DoStepDynamics(double step_size)
Advance the dynamics simulation by a single time step of given length.
Definition: ChSystem.cpp:1632
ChQuaterniond QuatFromAngleZ(double angle)
Convert from a rotation about Z axis to a quaternion.
Definition: ChRotation.cpp:196
Class for a physical system in which contact is modeled using a smooth (penalty-based) method.
Definition: ChSystemSMC.h:30
Sparse supernodal LU factorization.
Bullet-based collision detection system.
Interpolation function:
Definition: ChFunctionInterp.h:31
virtual double GetVal(double x) const override
Return the function output for input x.
Definition: ChFunctionRamp.h:43
Markers are auxiliary reference frames attached to a rigid body and moving with the body.
Definition: ChMarker.h:35
void BuildBeam(std::shared_ptr< ChMesh > mesh, std::shared_ptr< ChBeamSectionEuler > sect, const int N, const ChVector3d A, const ChVector3d B, const ChVector3d Ydir)
Add beam FEM elements to the mesh to create a segment beam from point A to point B,...
Definition: ChBuilderBeam.cpp:25
Sequence function: y = sequence_of_functions(f1(y), f2(y), f3(y)) All other function types can be ins...
Definition: ChFunctionSequence.h:66
Class for defining a camera point of view with basic settings.
Definition: ChCamera.h:29
Class for accessing the Matlab engine with a C++ wrapper.
Definition: ChMatlabEngine.h:45
Representation of a moving 3D.
Definition: ChFrameMoving.h:27
void EnableShadows(std::shared_ptr< ChPhysicsItem > item=nullptr)
Enable shadow maps for all visual models in a scene or only for a single physics item.
Definition: ChVisualSystemIrrlicht.cpp:472
Chrono core utilities.
Definition: ChBenchmark.h:27
ChVector3< Real > TransformPointParentToLocal(const ChVector3< Real > &v) const
Transforms a point from the parent coordinate system to local coordinate system.
Definition: ChCoordsys.h:198
Material data for a collision surface for use with non-smooth (complementarity) contact method.
Definition: ChContactMaterialNSC.h:32
void SetCameraVertical(CameraVerticalDir upDir)
Set the camera up vector (default: Z).
Definition: ChVisualSystemVSG.cpp:642
ChVector3< double > ChVector3d
Alias for double-precision vectors.
Definition: ChVector3.h:283
virtual void Initialize() override
Initialize the visualization system.
Definition: ChVisualSystemVSG.cpp:672
void SetWindowTitle(const std::string &win_title)
Set the windoiw title (default "").
Definition: ChVisualSystemIrrlicht.cpp:138
void AddAll()
Add all ChPhysicsItem objects in the system to the list of objects to render.
Definition: ChPovRay.cpp:88
y direction of a reference frame
void SetParameters(unsigned int mMaxHullCount=256, unsigned int mMaxMergeHullCount=256, unsigned int mMaxHullVertices=64, float mConcavity=0.2f, float mSmallClusterThreshold=0.0f, float mFuseTolerance=1e-9)
Set the parameters for this convex decomposition algorithm.
Definition: ChConvexDecomposition.cpp:326
void AddBoxGeometry(ChBody *body, ChContactMaterialSharedPtr material, const ChVector3d &size, const ChVector3d &pos, const ChQuaterniond &rot, bool visualization, ChVisualMaterialSharedPtr vis_material)
Add a box collision shape and optionally a corresponding visualization asset to the specified body.
Definition: ChUtilsCreators.cpp:75
void ConcatenatePreTransformation(const ChFrameMoving< Real > &F)
Apply a transformation (rotation and translation) represented by another frame.
Definition: ChFrameMoving.h:297
virtual void AttachSystem(ChSystem *sys) override
Attach another Chrono system to the run-time visualization system.
Definition: ChVisualSystemIrrlicht.cpp:165
virtual void SetSolver(std::shared_ptr< ChSolver > newsolver)
Attach a solver (derived from ChSolver) for use by this system.
Definition: ChSystem.cpp:319
static void FromAbaqusFile(std::shared_ptr< ChMesh > mesh, const char *filename, std::shared_ptr< ChContinuumMaterial > my_material, std::map< std::string, std::vector< std::shared_ptr< ChNodeFEAbase > > > &node_sets, ChVector3d pos_transform=VNULL, ChMatrix33<> rot_transform=ChMatrix33<>(1), bool discard_unused_nodes=true)
Load tetrahedrons, if any, saved in a .inp file for Abaqus.
Definition: ChMeshFileLoader.cpp:206
Class defining quaternion objects, that is four-dimensional numbers.
Definition: ChQuaternion.h:34
Class for post processing implementation that generates scripts for POVray.
Definition: ChPovRay.h:33
Utility class for creating complex beams using ChElementCableANCF elements, for example subdivides a ...
Definition: ChBuilderBeam.h:91
ChVector3< int > ChVector3i
Alias for integer vectors.
Definition: ChVector3.h:301
virtual unsigned int GetHullCount()
Get the number of computed hulls after the convex decomposition.
Definition: ChConvexDecomposition.cpp:394
Namespace with classes for the cosimulation module.
Definition: ChApiCosimulation.h:50
virtual bool Run() override
Run the Irrlicht device.
Definition: ChVisualSystemIrrlicht.cpp:240
irr::scene::ILightSceneNode * AddLight(const ChVector3d &pos, double radius, ChColor color=ChColor(0.7f, 0.7f, 0.7f))
Add a point light to the scene.
Definition: ChVisualSystemIrrlicht.cpp:399
bool GetVariable(ChMatrixDynamic< double > &mmatr, std::string varname)
Fetch a matrix from Matlab environment, specifying its name as variable.
Definition: ChMatlabEngine.cpp:120
static void fillIrrlichtMeshFromCascade(scene::IMesh *pMesh, const TopoDS_Shape &mshape, double deflection=1, bool relative_deflection=false, double angulardeflection=0.5, video::SColor clr=video::SColor(255, 255, 255, 255))
Function to convert an OpenCASCADE shape into a Irrlicht mesh, for visualization.
Definition: ChCascadeIrrMeshTools.h:122
Main Irrlicht namespace (Chrono extensions).
Definition: ChCascadeIrrMeshTools.h:47
Eigen::Matrix< T, Eigen::Dynamic, 1, Eigen::ColMajor > ChVectorDynamic
Column vector with dynamic size (i.e., with size unknown at compile time).
Definition: ChMatrix.h:112
VSG-based Chrono run-time visualization system.
Definition: ChVisualSystemVSG.h:61
Loads acting on multiple ChLoadable items.
Definition: ChLoad.h:288
Namespace with classes for the CASCADE module.
Definition: ChApiCASCADE.h:51
Main namespace for the Chrono package.
Definition: ChCamera.cpp:17
double GetChTime() const
Get the simulation time of this system.
Definition: ChSystem.h:154
void SetTimestepperType(ChTimestepper::Type type)
Set the method for time integration (time stepper type).
Definition: ChSystem.cpp:412
virtual void AttachSystem(ChSystem *sys)
Attach a Chrono system to this visualization system.
Definition: ChVisualSystem.cpp:26
virtual void BindItem(std::shared_ptr< ChPhysicsItem > item) override
Process the visual assets for the spcified physics item.
Definition: ChVisualSystemIrrlicht.cpp:665
void SetLight(ChVector3d location, ChColor color, bool cast_shadow)
Set the default light position and color - will write this in the output .pov file.
Definition: ChPovRay.cpp:157
virtual void AddShaft(std::shared_ptr< ChShaft > shaft)
Attach a shaft to the underlying assembly.
Definition: ChSystem.cpp:138
virtual double GetDer(double x) const override
Return the first derivative of the function.
Definition: ChFunctionRamp.h:44
void AddLogo(const std::string &logo_filename=GetChronoDataFile("logo_chronoengine_alpha.png"))
Add a logo in a 3D scene.
Definition: ChVisualSystemIrrlicht.cpp:333
void SetAngularCoeff(double ang_coeff)
Set the angular coefficient.
Definition: ChFunctionRamp.h:54
virtual double GetDer2(double x) const override
Return the second derivative of the function.
Definition: ChFunctionSine.cpp:36
void drawSegment(ChVisualSystemIrrlicht *vis, ChVector3d start, ChVector3d end, chrono::ChColor col, bool use_Zbuffer)
Draw line segments in 3D space with given color.
Definition: ChIrrTools.cpp:660
Class defining basic geometric information for collision pairs.
Definition: ChCollisionInfo.h:26
__host__ __device__ int max(int a, int b)
Return the maximum of two integer numbers.
Definition: custom_math.h:59
virtual void SetCollisionSystemType(ChCollisionSystem::Type type)
Set the collision detection system used by this Chrono system to the specified type.
Definition: ChSystem.cpp:324
virtual void AddBody(std::shared_ptr< ChBody > body)
Attach a body to the underlying assembly.
Definition: ChSystem.cpp:132
Irrlicht base classes (Chrono extensions).
Definition: ChIrrTools.cpp:23
Type
Supported collision systems.
Definition: ChCollisionSystem.h:44
bool Eval(std::string mstring)
Evaluate a Matlab instruction (as a string). If error happens while executing, returns false.
Definition: ChMatlabEngine.cpp:63
Loader for ChLoadableU objects (which support line loads), for loads of distributed type.
Definition: ChLoaderU.h:48
void AddPoint(double x, double y, bool overwrite_if_existing=false)
Add a point to the table.
Definition: ChFunctionInterp.cpp:26
Namespace for FEA classes.
Definition: ChVisualShapeFEA.h:28
Class for a physical system in which contact is modeled using a non-smooth (complementarity-based) me...
Definition: ChSystemNSC.h:29
virtual bool Run() override
Check if rendering is running.
Definition: ChVisualSystemVSG.cpp:925
void Update(double mytime, bool update_assets=true)
Updates all the auxiliary data and children of bodies, forces, links, given their current state.
Definition: ChSystem.cpp:694
ChCoordsys< Real > & GetCoordsys()
Return both current rotation and translation as a ChCoordsys object.
Definition: ChFrame.h:143
Eigen::Map< Eigen::Matrix< Real, 3, 1 > > eigen()
View this 3d vector as an Eigen vector.
Definition: ChVector3.h:73
void drawSpring(ChVisualSystemIrrlicht *vis, double radius, ChVector3d start, ChVector3d end, chrono::ChColor col, int resolution, double turns, bool use_Zbuffer)
Draw a spring in 3D space with given color.
Definition: ChIrrTools.cpp:712
virtual void Setup()
Counts the number of bodies and links.
Definition: ChSystem.cpp:620
Constant acceleration function.
Definition: ChFunctionConstAcc.h:36
ChVector3d vpA
coll.point on A, in abs coords
Definition: ChCollisionInfo.h:32
Eigen::Matrix< T, M, N, Eigen::RowMajor > ChMatrixNM
Dense matrix with fixed size (known at compile time) and row-major storage.
Definition: ChMatrix.h:80
Class for incremental form of state of time-integrable objects.
Definition: ChState.h:123
static void SetDefaultSuggestedEnvelope(double envelope)
Set the default envelope value.
Definition: ChCollisionModel.cpp:81
Namespace with classes for the VSG module.
Definition: ChApiVSG.h:51
A single object of this class must be instantiated before using all classes related to sockets,...
Definition: ChSocket.h:234
void SetWindowSize(unsigned int width, unsigned int height)
Set the window size (default 640x480).
Definition: ChVisualSystemIrrlicht.cpp:134
Interface for functions that uses a callback to return a Y value, as a ZERO_ORDER_HOLD (zero order ho...
Definition: ChFunctionSetpoint.h:108
ChVector2< int > ChVector2i
Alias for integer vectors.
Definition: ChVector2.h:227
std::vector< std::shared_ptr< ChNodeFEAxyzrot > > & GetLastBeamNodes()
Access the list of nodes used by the last built beam.
Definition: ChBuilderBeam.h:86
void SetLoadIncrementCallback(std::shared_ptr< LoadIncrementCallback > callback)
Set the callback to be called at each iteration.
Definition: ChStaticAnalysis.h:264
Irrlicht-based Chrono run-time visualization system.
Definition: ChVisualSystemIrrlicht.h:51
Class to be used as a callback interface for some user defined action to be taken each time a contact...
Definition: ChContactContainer.h:70
void SetResidualTolerance(double tol)
Set stopping criteria based on norm of residual and the specified tolerance.
Definition: ChStaticAnalysis.cpp:779
Class to be used as a callback interface for updating the system at each step of load increment.
Definition: ChStaticAnalysis.h:252