AGX Dynamics 2.37.3.3
Loading...
Searching...
No Matches
agxUtil Namespace Reference

The agxUtil namespace contain classes and methods for utility functionality. More...

Namespaces

namespace  convert
 
namespace  ConvexReaderWriter
 Functions for generating Convex shapes from meshes, and for serializing them.
 
namespace  deprecated
 
namespace  RawMeshReader
 Functions for generating Trimesh shapes from meshes, and for serializing them.
 
namespace  TrimeshReaderWriter
 Functions for generating Trimesh shapes from meshes, and for serializing them.
 

Classes

class  BodyLocalOffset
 
class  BSpline
 https://en.wikipedia.org/wiki/B-spline More...
 
class  CardinalSpline
 A Spline constructed of piecewise third-order polynomials which pass through a set of control points. More...
 
class  CollectBodiesAndWiresVisitor
 This visitor will visit each rigid body and wire in an assembly (or collection) and extract them to a vector with all bodies. More...
 
class  ConstraintHolder
 Utility class to hold custom implementations of constraints. More...
 
class  ConvexHull2D
 Utility class to create a convex hull in a plane given point cloud. More...
 
class  CPCatmullRomBSpline
 https://en.wikipedia.org/wiki/Centripetal_Catmull%E2%80%93Rom_spline More...
 
class  CubicSpline
 A Spline constructed of piecewise third-order polynomials which pass through a set of control points. More...
 
class  ExponentialMovingAverageStatistic
 Exponential moving average statistic. More...
 
class  GeneralContactEventListener
 Utility class to get contact event callbacks to any class having the methods implemented. More...
 
class  GeneralStepListener
 Utility class to get step event callbacks to any class having the methods implemented. More...
 
class  HeightFieldGenerator
 
class  HermiteSpline
 https://en.wikipedia.org/wiki/Hermite_spline More...
 
struct  JumpRequestWireOption
 Jump request options for wire nodes which parent isn't the given assembly/collection. More...
 
struct  LargerThanPred
 Larger than operator to e.g., sort functions. More...
 
struct  LessThanPred
 Less than operator to e.g., sort functions. More...
 
class  MedianStatistic
 Median statistic that keeps a history of a number of observations and reports the median, i.e., middle element in sorted order, of that. More...
 
class  NonUniformCardinalSpline
 A Spline constructed of piecewise third-order polynomials which pass through a set of control points. More...
 
class  OnScopeExit
 Register a callback to be called at the end of the current scope. More...
 
class  ParallelTrimeshDeformer
 
class  ParameterizedCatmullRomSpline
 Special case of a cardinal spline. More...
 
class  PointCurve
 Utility class curve defined by a set of points. More...
 
class  PrimitiveMeshGenerator
 
class  RawMesh
 A class to hold a general represenation of a mesh with arbitrary number of vertices in a face. More...
 
class  SceneRoot
 
struct  ShapeOrientation
 Specify the orientation of cylinder, capsule for computeOrientedCylinder and computeOrientedCapsule. More...
 
class  SmoothingFilter
 
class  Spline
 Base class for splines. More...
 
class  Statistic
 Pure virtual statistic class containing the fundamentals for implementing a statistics method. More...
 
class  StatisticHandle
 Extra level of indirection provided for use by garbage collected languages. More...
 
class  StepEventCallback
 Helper to use lambdas as preCollide, pre, post and last step events. More...
 
struct  TaskGraphWriter
 
class  TextureAtlasGenerator
 This class will take an input mesh and recompute texture coordinates to fit on a texture atlas. More...
 
class  TimerBlock
 Utility class to time a scope. More...
 
class  TrimeshDeformer
 
class  TrimeshInterpolator
 
struct  Uri
 
class  VariableSmoothFactorEMAStatistic
 Variable Smooth Factor Exponential Moving Average statistic. More...
 
class  VariableSmoothingFactorFilter
 Variable Smooth Factor Exponential Moving Average filter. More...
 

Typedefs

typedef agx::observer_ptr< const BodyLocalOffsetBodyLocalOffsetConstObserver
 
typedef agx::ref_ptr< const BodyLocalOffsetBodyLocalOffsetConstRef
 
typedef agx::observer_ptr< BodyLocalOffsetBodyLocalOffsetObserver
 
typedef agx::Vector< BodyLocalOffsetObserverBodyLocalOffsetObserverVector
 
typedef agx::VectorPOD< BodyLocalOffset * > BodyLocalOffsetPtrVector
 
typedef agx::ref_ptr< BodyLocalOffsetBodyLocalOffsetRef
 
typedef agx::Vector< BodyLocalOffsetRefBodyLocalOffsetRefVector
 
typedef agx::ref_ptr< BSplineBSplineRef
 
typedef agx::ref_ptr< CardinalSplineCardinalSplineRef
 
typedef agx::ref_ptr< ConstraintHolderConstraintHolderRef
 
typedef agx::ref_ptr< CPCatmullRomBSplineCPCatmullRomBSplineRef
 
typedef agx::ref_ptr< CubicSplineCubicSplineRef
 
typedef agx::observer_ptr< const HeightFieldGeneratorHeightFieldGeneratorConstObserver
 
typedef agx::ref_ptr< const HeightFieldGeneratorHeightFieldGeneratorConstRef
 
typedef agx::observer_ptr< HeightFieldGeneratorHeightFieldGeneratorObserver
 
typedef agx::ref_ptr< HeightFieldGeneratorHeightFieldGeneratorRef
 
typedef agx::ref_ptr< HermiteSplineHermiteSplineRef
 
typedef agx::ref_ptr< NonUniformCardinalSplineNonUniformCardinalSplineRef
 
typedef agx::observer_ptr< const ParallelTrimeshDeformerParallelTrimeshDeformerConstObserver
 
typedef agx::ref_ptr< const ParallelTrimeshDeformerParallelTrimeshDeformerConstRef
 
typedef agx::observer_ptr< ParallelTrimeshDeformerParallelTrimeshDeformerObserver
 
typedef agx::ref_ptr< ParallelTrimeshDeformerParallelTrimeshDeformerRef
 
typedef agx::ref_ptr< ParameterizedCatmullRomSplineParameterizedCatmullRomSplineRef
 
typedef agx::observer_ptr< const RawMeshRawMeshConstObserver
 
typedef agx::ref_ptr< const RawMeshRawMeshConstRef
 
typedef agx::observer_ptr< RawMeshRawMeshObserver
 
typedef agx::Vector< RawMeshObserverRawMeshObserverVector
 
typedef agx::VectorPOD< RawMesh * > RawMeshPtrVector
 
typedef agx::ref_ptr< RawMeshRawMeshRef
 
typedef agx::Vector< RawMeshRefRawMeshRefVector
 
typedef agx::ref_ptr< SmoothingFilterSmoothingFilterRef
 
typedef agx::ref_ptr< SplineSplineRef
 
typedef agx::observer_ptr< const StatisticHandleStatisticHandleConstObserver
 
typedef agx::ref_ptr< const StatisticHandleStatisticHandleConstRef
 
typedef agx::observer_ptr< StatisticHandleStatisticHandleObserver
 
typedef agx::ref_ptr< StatisticHandleStatisticHandleRef
 
typedef agx::observer_ptr< const TrimeshDeformerTrimeshDeformerConstObserver
 
typedef agx::ref_ptr< const TrimeshDeformerTrimeshDeformerConstRef
 
typedef agx::observer_ptr< TrimeshDeformerTrimeshDeformerObserver
 
typedef agx::ref_ptr< TrimeshDeformerTrimeshDeformerRef
 
typedef agx::observer_ptr< const TrimeshInterpolatorTrimeshInterpolatorConstObserver
 
typedef agx::ref_ptr< const TrimeshInterpolatorTrimeshInterpolatorConstRef
 
typedef agx::observer_ptr< TrimeshInterpolatorTrimeshInterpolatorObserver
 
typedef agx::ref_ptr< TrimeshInterpolatorTrimeshInterpolatorRef
 
typedef agx::ref_ptr< VariableSmoothingFactorFilterVariableSmoothingFactorFilterRef
 

Enumerations

enum class  SegmentType { FIRST , INTERMEDIATE , LAST }
 

Functions

AGXPHYSICS_EXPORT void addGroup (const agx::RigidBody *body, unsigned id)
 For the specified body, add the collision group ID to its geometries.
 
AGXPHYSICS_EXPORT void addParentVelocity (const agx::RigidBody *parentBody, agx::RigidBody *body)
 body will get the parents velocity added to its velocity as if it was rigidly attached.
 
AGXPHYSICS_EXPORT agx::AffineMatrix4x4 calculateCylinderTransform (const agx::Vec3 &startPoint, const agx::Vec3 &endPoint)
 Calculates transform that can be used for cylinders/capsules like geometries.
 
void AGXPHYSICS_EXPORT changeWindingToCounterclockwise (agx::UInt32Vector &indices)
 Changes Winding from clockwise to counterclockwise.
 
AGXPHYSICS_EXPORT bool computeOrientedBox (const agx::Vec3Vector &vertices, agx::Vec3 &halfExtents, agx::AffineMatrix4x4 &transform)
 Computes an oriented bounding box around the specified vertices.
 
AGXPHYSICS_EXPORT bool computeOrientedCapsule (const agx::Vec3Vector &vertices, agx::Vec2 &radiusHeight, agx::AffineMatrix4x4 &localRotation, agxUtil::ShapeOrientation::Orientation orientation=agxUtil::ShapeOrientation::MINIMIZE_VOLUME)
 Compute the radius, height and rotation of a capsule that encapsulates a specified box specified by halfExtents The orientation flag can be used to orient the cylinder along one of the principal axes of the box.
 
AGXPHYSICS_EXPORT bool computeOrientedCylinder (const agx::Vec3Vector &vertices, agx::Vec2 &radiusHeight, agx::AffineMatrix4x4 &localRotation, agxUtil::ShapeOrientation::Orientation orientation=agxUtil::ShapeOrientation::MINIMIZE_VOLUME)
 Compute the radius, height and rotation of a cylinder that encapsulates a specified box specified by halfExtents The orientation flag can be used to orient the cylinder along one of the principal axes of the box.
 
template<typename ContainerT >
ContainerT copyContainerMemory (const ContainerT &container)
 Returns a copy of the passed container.
 
AGXPHYSICS_EXPORT agxControl::EventSensorcreateSinkOnGeometry (agxCollide::Geometry *geometry, bool onlyIncludeEmittedBodies)
 Utillity function for creating a "sink" on a geometry that will remove rigid bodies and particles that come into contact with it.
 
AGXPHYSICS_EXPORT bool extractConstraints (agx::ConstraintPtrVector &vec, agx::DynamicsSystem *system)
 Utility function to extract all constraints from the system.
 
AGXPHYSICS_EXPORT bool extractGeometries (agxCollide::GeometryPtrVector &geometries, agx::RigidBody *body)
 Utility function to extract all geometries from a RigidBody.
 
AGXPHYSICS_EXPORT bool extractGeometries (agxCollide::GeometryPtrVector &geometries, agxSDK::Assembly *assembly)
 Utility function to extract all geometries from an assembly (and its sub-assemblies), including geometries found in RigidBodies which are a part of the assembly (and sub-assemblies).
 
AGXPHYSICS_EXPORT bool extractGeometries (agxCollide::GeometryPtrVector &vec, agxCollide::Space *space)
 Utility function to extract all geometries from the space into a vector.
 
AGXPHYSICS_EXPORT bool extractRigidBodies (agx::RigidBodyPtrVector &bodies, agxSDK::Assembly *assembly)
 Utility function to extract all Rigid Bodies from an assembly (and its sub-assemblies).
 
template<typename ContainerT >
void freeContainerMemory (ContainerT &container)
 Free the memory held by the given container by swapping it with a default-constructed instance.
 
AGXPHYSICS_EXPORT size_t getContactMaterialVector (agxSDK::MaterialManager *mgr, agx::ContactMaterialPtrVector &contactMaterials)
 Get all contact materials from the material manager and add them to the supplied vector.
 
AGXPHYSICS_EXPORT size_t getMaterialVector (agxSDK::MaterialManager *mgr, agx::MaterialPtrVector &materials)
 Get all materials from the material manager and add them to the supplied vector.
 
AGXPHYSICS_EXPORT size_t getMeshData (const agxCollide::Mesh *mesh, agx::Vec3Vector &vertices, agx::UInt32Vector &indices)
 Extract vertices and indices from mesh.
 
template<typename ContainerT >
void insertionSort (ContainerT &container)
 Insertion sort, supports std::valarray.
 
template<typename ContainerT , typename Pred >
void insertionSort (ContainerT &container, Pred pred)
 Insertion sort, supports std::valarray.
 
AGXPHYSICS_EXPORT bool isConvexMesh (const agxCollide::Mesh *mesh, agx::Real threshold=1E-5)
 Algorithm for determining if a mesh is convex.
 
template<typename ContainerT >
agx::Bool isSorted (const ContainerT &container)
 std::valarray friendly is sorted function.
 
AGXPHYSICS_EXPORT size_t jumpRequest (agxSDK::Assembly *collection, agx::RigidBody *parentBody, const agx::AffineMatrix4x4 &parentBodyWorldTransform, agx::UInt32 wireOptions=agx::UInt32(0))
 This method will perform a "jump request" will all bodies in the assembly, including bodies which are part of wires.
 
void AGXPHYSICS_EXPORT mergeDuplicateVertices (const agx::Vec3Vector &originalVertices, const agx::UInt32Vector &originalIndices, agx::Vec3Vector &remainingVertices, agx::UInt32Vector &remainingIndices, agx::Real precision)
 Merged duplicate vertices (distance is <= precision).
 
template<typename Callback >
OnScopeExit< Callback > onScopeExit (Callback &&callback)
 
AGXPHYSICS_EXPORT bool reduceMesh (const agx::Vec3Vector &vertices, const agx::UInt32Vector &indices, agx::Vec3Vector &outVertices, agx::UInt32Vector &outIndices, double reductionRatio=0.5, double aggressiveness=7.0)
 Perform mesh reduction using Fast-Quadric-Mesh.
 
AGXPHYSICS_EXPORT void removeGroup (const agx::RigidBody *body, unsigned id)
 For the specified body, remove the collision group ID to its geometries.
 
AGXPHYSICS_EXPORT bool setBodyMaterial (agx::RigidBody *body, agx::Material *material)
 Utility function to loop through a body and set the material for associated geometry.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agx::RigidBody *body, agxSDK::Assembly *assembly, bool enable)
 Enable or disable the collision between all geometries found in Assembly assembly and in RigidBody body.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agx::RigidBody *body, bool enable)
 Enable or disable collision for all geometries in a RigidBody.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agx::RigidBody *body, const agxCollide::Geometry *geom, bool enable)
 Enable or disable the collision between all geometries in RigidBody body the geometry geom.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agx::RigidBody *rb1, agx::RigidBody *rb2, bool enable)
 Enable or disable the collision between all geometries in RigidBody rb1 and RigidBody rb2.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agxCollide::Geometry *geo, agxSDK::Assembly *assembly, bool enable)
 Enable or disable the collision between all geometries found in Assembly assembly and a Geometry geo.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agxSDK::Assembly *a1, agxSDK::Assembly *a2, bool enable)
 Enable or disable the collision between all geometries found in Assembly g1 and in Assembly g2.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agxSDK::Assembly *assembly, agx::RigidBody *body, bool enable)
 Enable or disable the collision between all geometries found in Assembly assembly and in RigidBody body.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (agxSDK::Assembly *assembly, agxCollide::Geometry *geo, bool enable)
 Enable or disable the collision between all geometries found in Assembly assembly and a Geometry geo.
 
AGXPHYSICS_EXPORT bool setEnableCollisions (const agxCollide::Geometry *geom, agx::RigidBody *body, bool enable)
 Enable or disable the collision between all geometries in RigidBody body the geometry geom.
 
AGXPHYSICS_EXPORT bool setEnableGeometries (agx::RigidBody *body, bool enable)
 Enable or disable all geometries in a RigidBody.
 
AGXPHYSICS_EXPORT void setMotionControl (agx::RigidBodyPtrVector &bodies, agx::RigidBody::MotionControl motionControl)
 Utility function to set motion control for a vector of rigid bodies.
 
AGXPHYSICS_EXPORT agx::Vec3 transformPointFromTo (const agx::Vec3 point, const agx::RigidBody *fromBody, const agx::RigidBody *toBody)
 Point transform from rigid body fromBody to rigid body toBody.
 
AGXPHYSICS_EXPORT agx::Vec3 transformVectorFromTo (const agx::Vec3 vec, const agx::RigidBody *fromBody, const agx::RigidBody *toBody)
 Vector transform from rigid body fromBody to rigid body toBody.
 

Detailed Description

The agxUtil namespace contain classes and methods for utility functionality.

Typedef Documentation

◆ BodyLocalOffsetConstObserver

◆ BodyLocalOffsetConstRef

◆ BodyLocalOffsetObserver

◆ BodyLocalOffsetObserverVector

◆ BodyLocalOffsetPtrVector

◆ BodyLocalOffsetRef

◆ BodyLocalOffsetRefVector

◆ BSplineRef

Definition at line 334 of file Spline.h.

◆ CardinalSplineRef

Definition at line 239 of file Spline.h.

◆ ConstraintHolderRef

◆ CPCatmullRomBSplineRef

◆ CubicSplineRef

Definition at line 209 of file Spline.h.

◆ HeightFieldGeneratorConstObserver

◆ HeightFieldGeneratorConstRef

◆ HeightFieldGeneratorObserver

◆ HeightFieldGeneratorRef

◆ HermiteSplineRef

Definition at line 396 of file Spline.h.

◆ NonUniformCardinalSplineRef

◆ ParallelTrimeshDeformerConstObserver

◆ ParallelTrimeshDeformerConstRef

◆ ParallelTrimeshDeformerObserver

◆ ParallelTrimeshDeformerRef

◆ ParameterizedCatmullRomSplineRef

◆ RawMeshConstObserver

Definition at line 28 of file RawMesh.h.

◆ RawMeshConstRef

Definition at line 28 of file RawMesh.h.

◆ RawMeshObserver

Definition at line 28 of file RawMesh.h.

◆ RawMeshObserverVector

◆ RawMeshPtrVector

Definition at line 29 of file RawMesh.h.

◆ RawMeshRef

Definition at line 28 of file RawMesh.h.

◆ RawMeshRefVector

Definition at line 29 of file RawMesh.h.

◆ SmoothingFilterRef

◆ SplineRef

Definition at line 158 of file Spline.h.

◆ StatisticHandleConstObserver

◆ StatisticHandleConstRef

Definition at line 84 of file Statistic.h.

◆ StatisticHandleObserver

◆ StatisticHandleRef

Definition at line 84 of file Statistic.h.

◆ TrimeshDeformerConstObserver

◆ TrimeshDeformerConstRef

◆ TrimeshDeformerObserver

◆ TrimeshDeformerRef

◆ TrimeshInterpolatorConstObserver

◆ TrimeshInterpolatorConstRef

◆ TrimeshInterpolatorObserver

◆ TrimeshInterpolatorRef

◆ VariableSmoothingFactorFilterRef

Enumeration Type Documentation

◆ SegmentType

enum class agxUtil::SegmentType
strong
Enumerator
FIRST 
INTERMEDIATE 
LAST 

Definition at line 26 of file PointCurve.h.

Function Documentation

◆ addGroup()

AGXPHYSICS_EXPORT void agxUtil::addGroup ( const agx::RigidBody body,
unsigned  id 
)

For the specified body, add the collision group ID to its geometries.

Parameters
body- The body for which its geometries will have the id added.
id- The group id to be added

◆ addParentVelocity()

AGXPHYSICS_EXPORT void agxUtil::addParentVelocity ( const agx::RigidBody parentBody,
agx::RigidBody body 
)

body will get the parents velocity added to its velocity as if it was rigidly attached.

Parameters
parentBody- Body for which all of the other bodies velocities will be matched.
body- this body will get a new velocity that equals to its current velocity+parent velocity

◆ calculateCylinderTransform()

AGXPHYSICS_EXPORT agx::AffineMatrix4x4 agxUtil::calculateCylinderTransform ( const agx::Vec3 startPoint,
const agx::Vec3 endPoint 
)

Calculates transform that can be used for cylinders/capsules like geometries.

E.g.; aCylinder = createCylinder( length, radius ) aCylinder->setTransform( calculateCylinderTransform( startPoint, endPoint ) ) where 'length' has to be length( startPoint - endPoint ).

◆ changeWindingToCounterclockwise()

void AGXPHYSICS_EXPORT agxUtil::changeWindingToCounterclockwise ( agx::UInt32Vector indices)

Changes Winding from clockwise to counterclockwise.

Parameters
indicesThe indices (always 3 per triangle, see agxCollide/Trimesh.h). Expected to be in clockwise winding. Will reorder them to counterclockwise ordering.

◆ computeOrientedBox()

AGXPHYSICS_EXPORT bool agxUtil::computeOrientedBox ( const agx::Vec3Vector vertices,
agx::Vec3 halfExtents,
agx::AffineMatrix4x4 transform 
)

Computes an oriented bounding box around the specified vertices.

The result will a Vec3 with the half extents of the box and a transformation matrix that will orient/translate the principal axes of the box so that it encapsulates the vertices.

Parameters
vertices- The vertices from which an oriented bounding box will be created.
[out]halfExtents- Half extensts of the bounding box
[out]transform- Transformation that will translate and rotate a box with the size halfExtents so that it encapsulates the vertices.
Returns
true if a valid bounding box was computed

◆ computeOrientedCapsule()

AGXPHYSICS_EXPORT bool agxUtil::computeOrientedCapsule ( const agx::Vec3Vector vertices,
agx::Vec2 radiusHeight,
agx::AffineMatrix4x4 localRotation,
agxUtil::ShapeOrientation::Orientation  orientation = agxUtil::ShapeOrientation::MINIMIZE_VOLUME 
)

Compute the radius, height and rotation of a capsule that encapsulates a specified box specified by halfExtents The orientation flag can be used to orient the cylinder along one of the principal axes of the box.

Default is along Y.

Parameters
[in]vertices- The vertices from which an oriented capsule box will be created.
[out]radiusHeight- 2D vector with the radius, height result from the calculation
[out]localRotation- Transformation that will specify the local rotation of the capsule relative to the box
[in]orientation- Specifies which principal axis of the box that the capsule will be aligned to
Returns
true if a valid capsule could be computed

◆ computeOrientedCylinder()

AGXPHYSICS_EXPORT bool agxUtil::computeOrientedCylinder ( const agx::Vec3Vector vertices,
agx::Vec2 radiusHeight,
agx::AffineMatrix4x4 localRotation,
agxUtil::ShapeOrientation::Orientation  orientation = agxUtil::ShapeOrientation::MINIMIZE_VOLUME 
)

Compute the radius, height and rotation of a cylinder that encapsulates a specified box specified by halfExtents The orientation flag can be used to orient the cylinder along one of the principal axes of the box.

Default is along Y.

Parameters
[in]vertices- The vertices from which an oriented cylinder will be created.
[out]radiusHeight- 2D vector with the radius, height result from the calculation
[out]localRotation- Transformation that will specify the local rotation of the cylinder relative to the box
[in]orientation- Specifies which principal axis of the box that the cylinder will be aligned to
Returns
true if a valid cylinder could be computed

◆ copyContainerMemory()

template<typename ContainerT >
ContainerT agxUtil::copyContainerMemory ( const ContainerT &  container)

Returns a copy of the passed container.

This is useful in situations where an application that is using a different system allocator than the AGX Dynamics shared library needs to obtain a copy of a container that was allocated by AGX Dynamics. One example being where a container is created in the application and passed-by-value to some AGX Dynamics function. In this case the container will be allocated using the application system allocator, and destroyed by AGX Dynamics, which may cause runtime crashes. Obtaining a copy of the container through this function before passing it to AGX Dynamics will fix that issue.

 Example usage in application with different system allocator than AGX Dynamics **

const agx::String path = "path/to/a/service/license/file/agx.lfx";

The below function call may produce a runtime crash since the copy passed to loadLicenseFile() (passed by value) is allocated using the application system allocator, and is destroyed inside AGX Dynamics. agx::Runtime::instance()->loadLicenseFile(path); // <- may produce runtime crash.

Instead, we can pass a temporary agx::String object allocated by AGX Dynamics that will be moved from, thus the string is both allocated and deallocated by AGX Dynamics, avoiding the runtime crash. agx::Runtime::instance()->loadLicenseFile(agxUtil::copyContainerMemory(path));

◆ createSinkOnGeometry()

AGXPHYSICS_EXPORT agxControl::EventSensor * agxUtil::createSinkOnGeometry ( agxCollide::Geometry geometry,
bool  onlyIncludeEmittedBodies 
)

Utillity function for creating a "sink" on a geometry that will remove rigid bodies and particles that come into contact with it.

The sink is created by placing an agxControl::EventSensor on the geometry with operations that remove particles and bodies.

Parameters
geometry- the specified geometry to place the sink on.
onlyIncludeEmittedBodies- true if only rigid bodies that have been emitted should be removed, false otherwise. Note that particles will always be removed.
Note
"emitted" means that the agx::RigidBodyEmitter::rigidBodyIsEmitted(body) returns true.
Returns
the EventSensor object that contains the operations for removing bodies and particles.

◆ extractConstraints()

AGXPHYSICS_EXPORT bool agxUtil::extractConstraints ( agx::ConstraintPtrVector vec,
agx::DynamicsSystem system 
)

Utility function to extract all constraints from the system.

Parameters
vec- The vector where all the constraints in the system will be added.
system- The system which contains the constraints.
Returns
true if constraints were added to the vector, otherwise false.

◆ extractGeometries() [1/3]

AGXPHYSICS_EXPORT bool agxUtil::extractGeometries ( agxCollide::GeometryPtrVector geometries,
agx::RigidBody body 
)

Utility function to extract all geometries from a RigidBody.

Parameters
geometries- The vector where all the geometries found in the assembly will be placed
body- The RigidBody where to find all geometries.
Returns
true if geometries are added to the vector, otherwise false.

◆ extractGeometries() [2/3]

AGXPHYSICS_EXPORT bool agxUtil::extractGeometries ( agxCollide::GeometryPtrVector geometries,
agxSDK::Assembly assembly 
)

Utility function to extract all geometries from an assembly (and its sub-assemblies), including geometries found in RigidBodies which are a part of the assembly (and sub-assemblies).

Geometries of wires (that are added to the assembly) will also be extracted.

Parameters
geometries- The vector where all the geometries found in the assembly will be placed
assembly- The assembly where to find all geometries.
Returns
true if geometries are added to the vector, otherwise false.

◆ extractGeometries() [3/3]

AGXPHYSICS_EXPORT bool agxUtil::extractGeometries ( agxCollide::GeometryPtrVector vec,
agxCollide::Space space 
)

Utility function to extract all geometries from the space into a vector.

Parameters
vec- The vector where all the geometries in the system will be added.
space- The space which contains the geometries.
Returns
true if geometries were added to the vector, otherwise false.

◆ extractRigidBodies()

AGXPHYSICS_EXPORT bool agxUtil::extractRigidBodies ( agx::RigidBodyPtrVector bodies,
agxSDK::Assembly assembly 
)

Utility function to extract all Rigid Bodies from an assembly (and its sub-assemblies).

It will not extract bodies that has isPowerlineBody()==true. Bodies from wires will also be extracted

Parameters
bodies- The vector where all the bodies found in the assembly will be placed
assembly- The assembly where to find all bodies.
Returns
true if bodies are added to the vector, otherwise false.

◆ freeContainerMemory()

template<typename ContainerT >
void agxUtil::freeContainerMemory ( ContainerT &  container)

Free the memory held by the given container by swapping it with a default-constructed instance.

This is required when an application is using a different system allocator than the AGX Dynamics shared library and a container is passed by-value from AGX Dynamics to the application. When the container goes out of scope the application's system allocator will try to deallocate the container's buffer, a buffer that was allocated with AGX Dynamics' system allocator. This will either cause memory errors or a crash. By first calling freeContainerMemory the buffer will be freed inside AGX Dynamics, with AGX Dynamics' system allocator, and the application's system allocator will not need to do anything.

◆ getContactMaterialVector()

AGXPHYSICS_EXPORT size_t agxUtil::getContactMaterialVector ( agxSDK::MaterialManager mgr,
agx::ContactMaterialPtrVector contactMaterials 
)

Get all contact materials from the material manager and add them to the supplied vector.

Returns
number of extracted contact materials

◆ getMaterialVector()

AGXPHYSICS_EXPORT size_t agxUtil::getMaterialVector ( agxSDK::MaterialManager mgr,
agx::MaterialPtrVector materials 
)

Get all materials from the material manager and add them to the supplied vector.

Returns
number of extracted materials

◆ getMeshData()

AGXPHYSICS_EXPORT size_t agxUtil::getMeshData ( const agxCollide::Mesh mesh,
agx::Vec3Vector vertices,
agx::UInt32Vector indices 
)

Extract vertices and indices from mesh.

Parameters
mesh- mesh with data to extract
[out]vertices- vertices
[out]indices- indices
Returns
number of triangles added

◆ insertionSort() [1/2]

template<typename ContainerT >
void agxUtil::insertionSort ( ContainerT &  container)

Insertion sort, supports std::valarray.

Parameters
container- container to sort

Definition at line 391 of file agxUtil.h.

References insertionSort().

◆ insertionSort() [2/2]

template<typename ContainerT , typename Pred >
void agxUtil::insertionSort ( ContainerT &  container,
Pred  pred 
)

Insertion sort, supports std::valarray.

Parameters
container- container to sort
pred- Predicator used for comparison

Definition at line 369 of file agxUtil.h.

Referenced by insertionSort().

◆ isConvexMesh()

AGXPHYSICS_EXPORT bool agxUtil::isConvexMesh ( const agxCollide::Mesh mesh,
agx::Real  threshold = 1E-5 
)

Algorithm for determining if a mesh is convex.

For each triangle face, project all vertices on the triangle plane. If any vertex is above the plane with respect to some threshold value, we have detected a concavity and the mesh is considered non-convex.

Parameters
mesh- the mesh to test.
threshold- the minimum distance that a vertex can be above any triangle plane. ( Default: 1E-5 )
Returns
true if the mesh is convex within the specified threshold, false otherwise.

◆ isSorted()

template<typename ContainerT >
agx::Bool agxUtil::isSorted ( const ContainerT &  container)

std::valarray friendly is sorted function.

Returns
true if container is sorted

Definition at line 401 of file agxUtil.h.

◆ jumpRequest()

AGXPHYSICS_EXPORT size_t agxUtil::jumpRequest ( agxSDK::Assembly collection,
agx::RigidBody parentBody,
const agx::AffineMatrix4x4 parentBodyWorldTransform,
agx::UInt32  wireOptions = agx::UInt32(0) 
)

This method will perform a "jump request" will all bodies in the assembly, including bodies which are part of wires.

parentBody is the main body which will work as a parent, all other bodies will move relative to this rigid body. the transform parentBodyWorldTransform defines the new transform for the parent body, the target transform for parentBody. Also, make sure parentBody is part of the assembly collection

Parameters
collection- An Assembly which contain all bodies (including parentBody) and wires.
parentBody- The main rigid body, all other bodies will move relative to this body
parentBodyWorldTransform- The new requested transformation for the parentBody.
wireOptions- options how to handle wire nodes
Returns
the number of bodies that where moved, including parentBody

◆ mergeDuplicateVertices()

void AGXPHYSICS_EXPORT agxUtil::mergeDuplicateVertices ( const agx::Vec3Vector originalVertices,
const agx::UInt32Vector originalIndices,
agx::Vec3Vector remainingVertices,
agx::UInt32Vector remainingIndices,
agx::Real  precision 
)

Merged duplicate vertices (distance is <= precision).

Will also remove triangles which have been collapsed by merging vertices, and thus 2 or 3 of its vertices have become identical.

Parameters
originalVerticesThe original vertices.
originalIndicesThe original indices (always 3 per triangle, see agxCollide/Trimesh.h).
remainingVerticesThe remaining vertices. All pre-existing content will be overwritten.
remainingIndicesThe remaining indices (always 3 per triangle, see agxCollide/Trimesh.h). All pre-existing content will be overwritten.
precisionThe maximum distance for merging.

◆ onScopeExit()

template<typename Callback >
OnScopeExit< Callback > agxUtil::onScopeExit ( Callback &&  callback)

Definition at line 87 of file OnScopeExit.h.

◆ reduceMesh()

AGXPHYSICS_EXPORT bool agxUtil::reduceMesh ( const agx::Vec3Vector vertices,
const agx::UInt32Vector indices,
agx::Vec3Vector outVertices,
agx::UInt32Vector outIndices,
double  reductionRatio = 0.5,
double  aggressiveness = 7.0 
)

Perform mesh reduction using Fast-Quadric-Mesh.

Parameters
vertices- Vertices that will be target for reduction
indices- Indices that will be target for reduction. Must be a multiple of 3 (triangles) otherwise this method will return false
[out]outVertices- The vertices for the reduced mesh will be written into this vector
[out]outIndices- The indices for the reduced mesh will be written into this vector
reductionRatio- The desired reduction of triangle count. 1 == no reduction, 0.5 == 50% reduction. Clamped between [0.01, 1.0]
aggressiveness- (default = 7.0) Lower is faster and higher is better decimation. Valid range is [0.01,..]
Returns
true if mesh reduction results in > 1 triangle. False if indata is invalid or reduction results in < 1 triangle.

◆ removeGroup()

AGXPHYSICS_EXPORT void agxUtil::removeGroup ( const agx::RigidBody body,
unsigned  id 
)

For the specified body, remove the collision group ID to its geometries.

Parameters
body- The body for which its geometries will have the id removed.
id- The group id to be removed

◆ setBodyMaterial()

AGXPHYSICS_EXPORT bool agxUtil::setBodyMaterial ( agx::RigidBody body,
agx::Material material 
)

Utility function to loop through a body and set the material for associated geometry.

Parameters
body- The body for which all geometries will get a new material
material- The material that will be assigned to all geometries
Returns
true if the body had any geometries that could get a material assigned.

◆ setEnableCollisions() [1/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agx::RigidBody body,
agxSDK::Assembly assembly,
bool  enable 
)

Enable or disable the collision between all geometries found in Assembly assembly and in RigidBody body.

Parameters
body- Body containing geometries
assembly- Assembly containing bodies and geometries
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both assembly and body has geometries which could be disabled/enabled for collisions

◆ setEnableCollisions() [2/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agx::RigidBody body,
bool  enable 
)

Enable or disable collision for all geometries in a RigidBody.

Parameters
body- rigid body body with geometries
enable- If true, geometries will be enabled, if false, collisions will be disabled.
Returns
true if body has any geometries for which the collision where disabled

◆ setEnableCollisions() [3/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agx::RigidBody body,
const agxCollide::Geometry geom,
bool  enable 
)

Enable or disable the collision between all geometries in RigidBody body the geometry geom.

Parameters
body- rigid body
geom- Geometry
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if body has geometries that was disabled against geom

◆ setEnableCollisions() [4/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agx::RigidBody rb1,
agx::RigidBody rb2,
bool  enable 
)

Enable or disable the collision between all geometries in RigidBody rb1 and RigidBody rb2.

Parameters
rb1- First rigid body
rb2- Second rigid body
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both bodies have geometries, false if one or both of the bodies does not have any geometries.

◆ setEnableCollisions() [5/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agxCollide::Geometry geo,
agxSDK::Assembly assembly,
bool  enable 
)

Enable or disable the collision between all geometries found in Assembly assembly and a Geometry geo.

Parameters
geo- Geometry
assembly- Assembly containing bodies and geometries
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both assembly and body has geometries which could be disabled/enabled for collisions

◆ setEnableCollisions() [6/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agxSDK::Assembly a1,
agxSDK::Assembly a2,
bool  enable 
)

Enable or disable the collision between all geometries found in Assembly g1 and in Assembly g2.

Parameters
a1- First Assembly containing bodies and geometries
a2- Second Assembly containing bodies and geometries
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both assemblies have geometries which could be disabled/enabled for collisions

◆ setEnableCollisions() [7/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agxSDK::Assembly assembly,
agx::RigidBody body,
bool  enable 
)

Enable or disable the collision between all geometries found in Assembly assembly and in RigidBody body.

Parameters
assembly- Assembly containing bodies and geometries
body- Body containing geometries
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both assembly and body has geometries which could be disabled/enabled for collisions

◆ setEnableCollisions() [8/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( agxSDK::Assembly assembly,
agxCollide::Geometry geo,
bool  enable 
)

Enable or disable the collision between all geometries found in Assembly assembly and a Geometry geo.

Parameters
assembly- Assembly containing bodies and geometries
geo- Geometry
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if both assembly and body has geometries which could be disabled/enabled for collisions

◆ setEnableCollisions() [9/9]

AGXPHYSICS_EXPORT bool agxUtil::setEnableCollisions ( const agxCollide::Geometry geom,
agx::RigidBody body,
bool  enable 
)

Enable or disable the collision between all geometries in RigidBody body the geometry geom.

Parameters
geom- Geometry
body- rigid body
enable- If true, collisions will be enabled, if false, collisions will be disabled.
Returns
true if body has geometries that where disabled against geom

◆ setEnableGeometries()

AGXPHYSICS_EXPORT bool agxUtil::setEnableGeometries ( agx::RigidBody body,
bool  enable 
)

Enable or disable all geometries in a RigidBody.

Parameters
body- rigid body body with geometries
enable- If true, geometries will be enabled, if false, collisions will be disabled.
Returns
true if body has any geometries that where disabled

◆ setMotionControl()

AGXPHYSICS_EXPORT void agxUtil::setMotionControl ( agx::RigidBodyPtrVector bodies,
agx::RigidBody::MotionControl  motionControl 
)

Utility function to set motion control for a vector of rigid bodies.

Parameters
bodies- Vector of rigid bodies that will be modified.
motionControl- The desired motion control that all the bodies will get.

◆ transformPointFromTo()

AGXPHYSICS_EXPORT agx::Vec3 agxUtil::transformPointFromTo ( const agx::Vec3  point,
const agx::RigidBody fromBody,
const agx::RigidBody toBody 
)

Point transform from rigid body fromBody to rigid body toBody.

If a rigid body is null that body is assumed to be world (e.g, transformVectorFromTo( null, null, point ) == point).

Parameters
point- point in fromBody frame
fromBody- rigid body to transform from
toBody- rigid body to transform to

◆ transformVectorFromTo()

AGXPHYSICS_EXPORT agx::Vec3 agxUtil::transformVectorFromTo ( const agx::Vec3  vec,
const agx::RigidBody fromBody,
const agx::RigidBody toBody 
)

Vector transform from rigid body fromBody to rigid body toBody.

If a rigid body is null that body is assumed to be world (e.g, transformVectorFromTo( null, null, vec ) == vec).

Parameters
vec- vector in fromBody frame
fromBody- rigid body to transform from
toBody- rigid body to transform to