ReactPhysics3D  v0.10.1
C++ Physics engine library
reactphysics3d Namespace Reference

Namespace reactphysics3d. More...

Classes

class  Body
 This class represents a body. More...
 
class  RigidBody
 This class represents a rigid body of the physics engine. More...
 
struct  TreeNode
 This structure represents a node of the dynamic AABB tree. More...
 
class  DynamicAABBTreeOverlapCallback
 Overlapping callback method that has to be used as parameter of the reportAllShapesOverlappingWithNode() method. More...
 
class  DynamicAABBTreeRaycastCallback
 Raycast callback in the Dynamic AABB Tree called when the AABB of a leaf node is hit by the ray. More...
 
class  DynamicAABBTree
 This class implements a dynamic AABB tree that is used for broad-phase collision detection. More...
 
class  Collider
 A collider has a collision shape (box, sphere, capsule, ...) and is attached to a RigidBody. More...
 
class  CollisionCallback
 This abstract class can be used to register a callback for collision test queries. More...
 
class  ContactManifold
 This class represents a set of contact points between two bodies that all have a similar contact normal direction. More...
 
struct  ContactManifoldInfo
 This structure contains informations about a collision contact manifold computed during the narrow-phase collision detection. More...
 
struct  ContactPair
 This structure represents a pair of shapes that are in contact during narrow-phase. More...
 
struct  ContactPointInfo
 This structure contains informations about a collision contact computed during the narrow-phase collision detection. More...
 
class  ConvexMesh
 This class describes a convex mesh made of faces and vertices. More...
 
class  HalfEdgeStructure
 This class describes a polyhedron mesh made of faces and vertices. More...
 
class  HeightField
 This class represents a static height field that can be used to represent a terrain. More...
 
class  CapsuleVsCapsuleAlgorithm
 This class is used to compute the narrow-phase collision detection between two capsules collision shapes. More...
 
class  CapsuleVsConvexPolyhedronAlgorithm
 This class is used to compute the narrow-phase collision detection between a capsule and a convex polyhedron. More...
 
class  CollisionDispatch
 This is the collision dispatch configuration use in ReactPhysics3D. More...
 
class  ConvexPolyhedronVsConvexPolyhedronAlgorithm
 This class is used to compute the narrow-phase collision detection between two convex polyhedra. More...
 
class  Array
 This class represents a simple dynamic array with custom memory allocator. More...
 
class  GJKAlgorithm
 This class implements a narrow-phase collision detection algorithm. More...
 
class  VoronoiSimplex
 This class represents a simplex which is a set of 3D points. More...
 
class  NarrowPhaseCallback
 This abstract class is the base class for a narrow-phase collision callback class. More...
 
class  NarrowPhaseAlgorithm
 This abstract class is the base class for a narrow-phase collision detection algorithm. More...
 
struct  NarrowPhaseInfoBatch
 This structure collects all the potential collisions from the middle-phase algorithm that have to be tested during narrow-phase collision detection. More...
 
class  NarrowPhaseInput
 This structure contains everything that is needed to perform the narrow-phase collision detection. More...
 
class  SATAlgorithm
 This class implements the Separating Axis Theorem algorithm (SAT). More...
 
class  SphereVsCapsuleAlgorithm
 This class is used to compute the narrow-phase collision detection between a sphere collision shape and a capsule collision shape. More...
 
class  SphereVsConvexPolyhedronAlgorithm
 This class is used to compute the narrow-phase collision detection between a sphere and a convex polyhedron. More...
 
class  SphereVsSphereAlgorithm
 This class is used to compute the narrow-phase collision detection between two sphere collision shapes. More...
 
class  OverlapCallback
 This class can be used to register a callback for collision overlap queries between bodies. More...
 
class  PolygonVertexArray
 This class is used to describe the vertices and faces of a mesh. More...
 
struct  RaycastInfo
 This structure contains the information about a raycast hit. More...
 
class  RaycastCallback
 This class can be used to register a callback for ray casting queries. More...
 
struct  RaycastTest
 Structure RaycastTest. More...
 
class  AABB
 This class represents a bounding volume of type "Axis Aligned Bounding Box". More...
 
class  BoxShape
 This class represents a 3D box shape. More...
 
class  CapsuleShape
 This class represents a capsule collision shape that is defined around the Y axis. More...
 
class  CollisionShape
 This abstract class represents the collision shape associated with a body that is used during the narrow-phase collision detection. More...
 
class  ConvexTriangleAABBOverlapCallback
 This class represents a callback when an overlap occurs. More...
 
class  ConcaveMeshRaycastCallback
 Class ConcaveMeshRaycastCallback. More...
 
class  ConcaveMeshShape
 This class represents a static concave mesh shape. More...
 
class  TriangleCallback
 This class is used to encapsulate a callback method for a single triangle of a ConcaveMesh. More...
 
class  ConcaveShape
 This abstract class represents a concave collision shape associated with a body that is used during the narrow-phase collision detection. More...
 
class  ConvexMeshShape
 This class represents a convex mesh shape. More...
 
class  ConvexPolyhedronShape
 This abstract class represents a convex polyhedron collision shape associated with a body that is used during the narrow-phase collision detection. More...
 
class  ConvexShape
 This abstract class represents a convex collision shape associated with a body that is used during the narrow-phase collision detection. More...
 
class  HeightFieldShape
 This class represents a static height field that can be used to represent a terrain. More...
 
class  SphereShape
 This class represents a sphere collision shape that is centered at the origin and defined by its radius. More...
 
class  TriangleShape
 This class represents a triangle collision shape that is centered at the origin and defined three points. More...
 
class  TriangleMesh
 This class represents a mesh made of triangles. More...
 
class  TriangleVertexArray
 This class is used to describe the vertices and faces of a triangular mesh. More...
 
class  VertexArray
 This class is used to describe an array of vertices. More...
 
class  BallAndSocketJointComponents
 This class represent the component of the ECS with data for the BallAndSocketJoint. More...
 
class  BodyComponents
 This class represent the component of the ECS that contains data about a body. More...
 
class  ColliderComponents
 This class represent the component of the ECS that contains data about the the colliders of the different bodies. More...
 
class  Components
 This class represent the abstract class to store components of the ECS. More...
 
class  FixedJointComponents
 This class represent the component of the ECS with data for the FixedJoint. More...
 
class  HingeJointComponents
 This class represent the component of the ECS with data for the HingeJoint. More...
 
class  JointComponents
 This class represent the component of the ECS that contains generic information about all the joints. More...
 
class  RigidBodyComponents
 This class represent the component of the ECS that contains data about a rigid body. More...
 
class  SliderJointComponents
 This class represent the component of the ECS with data for the SliderJoint. More...
 
class  TransformComponents
 This class represent the component of the ECS that contains the transforms of the different entities. More...
 
struct  BallAndSocketJointInfo
 This structure is used to gather the information needed to create a ball-and-socket joint. More...
 
class  BallAndSocketJoint
 This class represents a ball-and-socket joint that allows arbitrary rotation between two bodies. More...
 
class  ContactPoint
 This class represents a collision contact point between two bodies in the physics engine. More...
 
struct  FixedJointInfo
 This structure is used to gather the information needed to create a fixed joint. More...
 
class  FixedJoint
 This class represents a fixed joint that is used to forbid any translation or rotation between two bodies. More...
 
struct  HingeJointInfo
 This structure is used to gather the information needed to create a hinge joint. More...
 
class  HingeJoint
 This class represents a hinge joint that allows arbitrary rotation between two bodies around a single axis. More...
 
struct  JointInfo
 This structure is used to gather the information needed to create a joint. More...
 
class  Joint
 This abstract class represents a joint between two bodies. More...
 
struct  SliderJointInfo
 This structure is used to gather the information needed to create a slider joint. More...
 
class  SliderJoint
 This class represents a slider joint. More...
 
class  Deque
 This class represents a Deque. More...
 
class  LinkedList
 This class represents a simple generic linked list. More...
 
class  Map
 This class represents a simple generic associative map. More...
 
class  Pair
 This class represents a simple generic pair. More...
 
class  Set
 This class represents a simple generic set. More...
 
class  Stack
 This class represents a simple generic stack. More...
 
struct  Entity
 This class is used to identify an entity in the Entity-Component-System. More...
 
class  EntityManager
 This class is responsible to manage the entities of the ECS. More...
 
class  EventListener
 This class can be used to receive notifications about events that occur during the simulation. More...
 
class  Island
 An island represent an isolated group of awake bodies that are connected with each other by some contraints (contacts or joints). More...
 
struct  Islands
 This class contains all the islands of bodies during a frame. More...
 
class  Material
 This class contains the material properties of a collider that will be use for the dynamics simulation like the friction coefficient or the bounciness of the rigid body. More...
 
struct  LastFrameCollisionInfo
 This structure contains collision info about the last frame. More...
 
class  OverlappingPairs
 This class contains pairs of two colliders that are overlapping during the broad-phase collision detection. More...
 
class  PhysicsCommon
 This class is a singleton that needs to be instanciated once at the beginning. More...
 
class  PhysicsWorld
 This class represents a physics world. More...
 
class  Matrix2x2
 This class represents a 2x2 matrix. More...
 
class  Matrix3x3
 This class represents a 3x3 matrix. More...
 
struct  Quaternion
 This class represents a quaternion. More...
 
struct  Ray
 This structure represents a 3D ray represented by two points. More...
 
class  Transform
 This class represents a position and an orientation in 3D. More...
 
struct  Vector2
 This class represents a 2D vector. More...
 
struct  Vector3
 This class represents a 3D vector. More...
 
class  DefaultAllocator
 This class represents a default memory allocator that uses standard C++ functions to allocated 16-bytes aligned memory. More...
 
class  HeapAllocator
 This class is used to efficiently allocate memory on the heap. More...
 
class  MemoryAllocator
 Abstract class with the basic interface of all the derived memory allocators. More...
 
class  MemoryManager
 The memory manager is used to store the different memory allocators that are used by the library. More...
 
class  PoolAllocator
 This class is used to efficiently allocate memory on the heap. More...
 
class  SingleFrameAllocator
 This class represent a memory allocator used to efficiently allocate memory on the heap that is used during a single frame. More...
 
class  AABBOverlapCallback
 This class represents a callback when two AABB overlap. More...
 
class  BroadPhaseRaycastCallback
 Callback called when the AABB of a leaf node is hit by a ray the broad-phase Dynamic AABB Tree. More...
 
class  BroadPhaseSystem
 This class represents the broad-phase collision detection. More...
 
class  CollisionDetectionSystem
 This class computes the collision detection algorithms. More...
 
struct  ConstraintSolverData
 This structure contains data from the constraint solver that are used to solve each joint constraint. More...
 
class  ConstraintSolverSystem
 This class represents the constraint solver that is used to solve constraints between the rigid bodies. More...
 
class  ContactSolverSystem
 This class represents the contact solver system that is used to solve rigid bodies contacts. More...
 
class  DynamicsSystem
 This class is responsible to compute and update the dynamics of the bodies that are simulated using physics. More...
 
class  SolveBallAndSocketJointSystem
 This class is responsible to solve the BallAndSocketJoint constraints. More...
 
class  SolveFixedJointSystem
 This class is responsible to solve the FixedJoint constraints. More...
 
class  SolveHingeJointSystem
 This class is responsible to solve the BallAndSocketJoint constraints. More...
 
class  SolveSliderJointSystem
 This class is responsible to solve the SliderJoint constraints. More...
 
class  DebugRenderer
 This class is used to display physics debug information directly into the user application view. More...
 
class  DefaultLogger
 This class is the default logger class used to log information, warnings or errors during the execution of the library code for easier debugging. More...
 
class  Logger
 This abstract class is the base class used to log information, warnings or errors during the execution of the library code for easier debugging. More...
 
struct  Message
 This structure represent a message that can be returned to the user. More...
 
class  QHHalfEdgeStructure
 This class describes a polyhedron mesh made of faces and vertices. More...
 
class  QuickHull
 This class implements the Quickhull algorithm to compute a convex mesh from a set of 3D points. More...
 

Typedefs

typedef unsigned int Bits
 
using uint = unsigned int
 
using uchar = unsigned char
 
using ushort = unsigned short
 
using luint = long unsigned int
 
using int8 = std::int8_t
 
using uint8 = std::uint8_t
 
using int16 = std::int16_t
 
using uint16 = std::uint16_t
 
using int32 = std::int32_t
 
using uint32 = std::uint32_t
 
using int64 = std::int64_t
 
using uint64 = std::uint64_t
 
using bodypair = Pair< Entity, Entity >
 
using decimal = float
 

Enumerations

enum class  NarrowPhaseAlgorithmType {
  NoCollisionTest , SphereVsSphere , SphereVsCapsule , CapsuleVsCapsule ,
  SphereVsConvexPolyhedron , CapsuleVsConvexPolyhedron , ConvexPolyhedronVsConvexPolyhedron
}
 Enumeration for the type of narrow-phase collision detection algorithm.
 
enum class  CollisionShapeType { SPHERE , CAPSULE , CONVEX_POLYHEDRON , CONCAVE_SHAPE }
 Type of collision shapes.
 
enum class  CollisionShapeName {
  TRIANGLE , SPHERE , CAPSULE , BOX ,
  CONVEX_MESH , TRIANGLE_MESH , HEIGHTFIELD
}
 Names of collision shapes.
 
enum class  TriangleRaycastSide { FRONT , BACK , FRONT_AND_BACK }
 Raycast test side for the triangle. More...
 
enum class  BodyType { STATIC , KINEMATIC , DYNAMIC }
 Enumeration for the type of a body STATIC : A static body has infinite mass, zero velocity but the position can be changed manually. More...
 
enum class  JointsPositionCorrectionTechnique { BAUMGARTE_JOINTS , NON_LINEAR_GAUSS_SEIDEL }
 Position correction technique used in the constraint solver (for joints). More...
 
enum class  ContactsPositionCorrectionTechnique { BAUMGARTE_CONTACTS , SPLIT_IMPULSES }
 Position correction technique used in the contact solver (for contacts) BAUMGARTE_CONTACTS : Faster but can be innacurate and can lead to unexpected bounciness in some situations (due to error correction factor being added to the bodies momentum). More...
 
enum class  JointType { BALLSOCKETJOINT , SLIDERJOINT , HINGEJOINT , FIXEDJOINT }
 Enumeration for the type of a constraint.
 

Functions

template<class T >
void hash_combine (std::size_t &seed, const T &v)
 This method is used to combine two hash values.
 
RP3D_FORCE_INLINE bool approxEqual (decimal a, decimal b, decimal epsilon=MACHINE_EPSILON)
 Function to test if two real numbers are (almost) equal We test if two numbers a and b are such that (a-b) are in [-EPSILON; EPSILON].
 
RP3D_FORCE_INLINE int clamp (int value, int lowerLimit, int upperLimit)
 Function that returns the result of the "value" clamped by two others values "lowerLimit" and "upperLimit".
 
RP3D_FORCE_INLINE decimal clamp (decimal value, decimal lowerLimit, decimal upperLimit)
 Function that returns the result of the "value" clamped by two others values "lowerLimit" and "upperLimit".
 
RP3D_FORCE_INLINE decimal min3 (decimal a, decimal b, decimal c)
 Return the minimum value among three values.
 
RP3D_FORCE_INLINE decimal max3 (decimal a, decimal b, decimal c)
 Return the maximum value among three values.
 
RP3D_FORCE_INLINE bool sameSign (decimal a, decimal b)
 Return true if two values have the same sign.
 
RP3D_FORCE_INLINE bool areParallelVectors (const Vector3 &vector1, const Vector3 &vector2)
 
RP3D_FORCE_INLINE bool areOrthogonalVectors (const Vector3 &vector1, const Vector3 &vector2)
 
RP3D_FORCE_INLINE Vector3 clamp (const Vector3 &vector, decimal maxLength)
 
RP3D_FORCE_INLINE Vector3 computeClosestPointOnSegment (const Vector3 &segPointA, const Vector3 &segPointB, const Vector3 &pointC)
 
RP3D_FORCE_INLINE void computeClosestPointBetweenTwoSegments (const Vector3 &seg1PointA, const Vector3 &seg1PointB, const Vector3 &seg2PointA, const Vector3 &seg2PointB, Vector3 &closestPointSeg1, Vector3 &closestPointSeg2)
 
RP3D_FORCE_INLINE void computeBarycentricCoordinatesInTriangle (const Vector3 &a, const Vector3 &b, const Vector3 &c, const Vector3 &p, decimal &u, decimal &v, decimal &w)
 
RP3D_FORCE_INLINE decimal computePlaneSegmentIntersection (const Vector3 &segA, const Vector3 &segB, const decimal planeD, const Vector3 &planeNormal)
 
RP3D_FORCE_INLINE decimal computePointToLineDistance (const Vector3 &linePointA, const Vector3 &linePointB, const Vector3 &point)
 
RP3D_FORCE_INLINE Array< Vector3clipSegmentWithPlanes (const Vector3 &segA, const Vector3 &segB, const Array< Vector3 > &planesPoints, const Array< Vector3 > &planesNormals, MemoryAllocator &allocator)
 
RP3D_FORCE_INLINE void clipPolygonWithPlane (const Array< Vector3 > &polygonVertices, const Vector3 &planePoint, const Vector3 &planeNormal, Array< Vector3 > &outClippedPolygonVertices)
 
RP3D_FORCE_INLINE Vector3 projectPointOntoPlane (const Vector3 &point, const Vector3 &unitPlaneNormal, const Vector3 &planePoint)
 
RP3D_FORCE_INLINE decimal computePointToPlaneDistance (const Vector3 &point, const Vector3 &planeNormal, const Vector3 &planePoint)
 
RP3D_FORCE_INLINE bool isPowerOfTwo (uint64 number)
 Return true if a number is a power of two.
 
RP3D_FORCE_INLINE uint64 nextPowerOfTwo64Bits (uint64 number)
 Return the next power of two larger than the number in parameter.
 
RP3D_FORCE_INLINE uint64 pairNumbers (uint32 number1, uint32 number2)
 Return an unique integer from two integer numbers (pairing function) Here we assume that the two parameter numbers are sorted such that number1 = max(number1, number2) http://szudzik.com/ElegantPairing.pdf.
 
RP3D_FORCE_INLINE Matrix2x2 operator+ (const Matrix2x2 &matrix1, const Matrix2x2 &matrix2)
 
RP3D_FORCE_INLINE Matrix2x2 operator- (const Matrix2x2 &matrix1, const Matrix2x2 &matrix2)
 
RP3D_FORCE_INLINE Matrix2x2 operator- (const Matrix2x2 &matrix)
 
RP3D_FORCE_INLINE Matrix2x2 operator* (decimal nb, const Matrix2x2 &matrix)
 
RP3D_FORCE_INLINE Matrix2x2 operator* (const Matrix2x2 &matrix, decimal nb)
 
RP3D_FORCE_INLINE Matrix2x2 operator* (const Matrix2x2 &matrix1, const Matrix2x2 &matrix2)
 
RP3D_FORCE_INLINE Vector2 operator* (const Matrix2x2 &matrix, const Vector2 &vector)
 
RP3D_FORCE_INLINE Matrix3x3 operator+ (const Matrix3x3 &matrix1, const Matrix3x3 &matrix2)
 
RP3D_FORCE_INLINE Matrix3x3 operator- (const Matrix3x3 &matrix1, const Matrix3x3 &matrix2)
 
RP3D_FORCE_INLINE Matrix3x3 operator- (const Matrix3x3 &matrix)
 
RP3D_FORCE_INLINE Matrix3x3 operator* (decimal nb, const Matrix3x3 &matrix)
 
RP3D_FORCE_INLINE Matrix3x3 operator* (const Matrix3x3 &matrix, decimal nb)
 
RP3D_FORCE_INLINE Matrix3x3 operator* (const Matrix3x3 &matrix1, const Matrix3x3 &matrix2)
 
RP3D_FORCE_INLINE Vector3 operator* (const Matrix3x3 &matrix, const Vector3 &vector)
 
RP3D_FORCE_INLINE Vector2 operator+ (const Vector2 &vector1, const Vector2 &vector2)
 
RP3D_FORCE_INLINE Vector2 operator- (const Vector2 &vector1, const Vector2 &vector2)
 
RP3D_FORCE_INLINE Vector2 operator- (const Vector2 &vector)
 
RP3D_FORCE_INLINE Vector2 operator* (const Vector2 &vector, decimal number)
 
RP3D_FORCE_INLINE Vector2 operator* (const Vector2 &vector1, const Vector2 &vector2)
 
RP3D_FORCE_INLINE Vector2 operator/ (const Vector2 &vector, decimal number)
 
RP3D_FORCE_INLINE Vector2 operator/ (const Vector2 &vector1, const Vector2 &vector2)
 
RP3D_FORCE_INLINE Vector2 operator* (decimal number, const Vector2 &vector)
 
RP3D_FORCE_INLINE bool approxEqual (const Vector2 &vec1, const Vector2 &vec2, decimal epsilon=MACHINE_EPSILON)
 
RP3D_FORCE_INLINE Vector3 operator+ (const Vector3 &vector1, const Vector3 &vector2)
 
RP3D_FORCE_INLINE Vector3 operator- (const Vector3 &vector1, const Vector3 &vector2)
 
RP3D_FORCE_INLINE Vector3 operator- (const Vector3 &vector)
 
RP3D_FORCE_INLINE Vector3 operator* (const Vector3 &vector, decimal number)
 
RP3D_FORCE_INLINE Vector3 operator/ (const Vector3 &vector, decimal number)
 
RP3D_FORCE_INLINE Vector3 operator/ (const Vector3 &vector1, const Vector3 &vector2)
 
RP3D_FORCE_INLINE Vector3 operator* (decimal number, const Vector3 &vector)
 
RP3D_FORCE_INLINE Vector3 operator* (const Vector3 &vector1, const Vector3 &vector2)
 

Variables

constexpr decimal REL_ERROR = decimal(1.0e-3)
 
constexpr decimal REL_ERROR_SQUARE = REL_ERROR * REL_ERROR
 
constexpr int MAX_ITERATIONS_GJK_RAYCAST = 32
 
const int NB_COLLISION_SHAPE_TYPES = 4
 
const decimal DECIMAL_SMALLEST = - std::numeric_limits<decimal>::max()
 Smallest decimal value (negative)
 
const decimal DECIMAL_LARGEST = std::numeric_limits<decimal>::max()
 Maximum decimal value.
 
const decimal MACHINE_EPSILON = std::numeric_limits<decimal>::epsilon()
 Machine epsilon.
 
constexpr decimal PI_RP3D = decimal(3.141592653589)
 Pi constant.
 
constexpr decimal PI_TIMES_2 = decimal(6.28318530)
 2*Pi constant
 
constexpr decimal DYNAMIC_TREE_FAT_AABB_INFLATE_PERCENTAGE = decimal(0.08)
 In the broad-phase collision detection (dynamic AABB tree), the AABBs are inflated by a constant percentage of its size to allow the collision shape to move a little bit without triggering a large modification of the tree each frame which can be costly.
 
constexpr uint8 NB_MAX_CONTACT_POINTS_IN_NARROWPHASE_INFO = 16
 Maximum number of contact points in a narrow phase info object.
 
constexpr uint8 NB_MAX_CONTACT_MANIFOLDS = 4
 Maximum number of contact manifolds in an overlapping pair.
 
constexpr uint8 NB_MAX_POTENTIAL_CONTACT_MANIFOLDS = 64
 Maximum number of potential contact manifolds in an overlapping pair.
 
constexpr uint8 NB_MAX_CONTACT_POINTS_IN_POTENTIAL_MANIFOLD = 255
 Maximum number of contact points in potential contact manifold.
 
constexpr decimal SAME_CONTACT_POINT_DISTANCE_THRESHOLD = decimal(0.01)
 Distance threshold to consider that two contact points in a manifold are the same.
 
constexpr uint8 GLOBAL_ALIGNMENT = 16
 Global alignment (in bytes) that all allocators must enforce.
 
const std::string RP3D_VERSION = std::string("0.10.1")
 Current version of ReactPhysics3D.
 

Detailed Description

Namespace reactphysics3d.

ReactPhysiscs3D namespace.

ReactPhysics3D namespace.

Namespace ReactPhysics3D.

Enumeration Type Documentation

◆ BodyType

Enumeration for the type of a body STATIC : A static body has infinite mass, zero velocity but the position can be changed manually.

A static body does not collide with other static or kinematic bodies. KINEMATIC : A kinematic body has infinite mass, the velocity can be changed manually and its position is computed by the physics engine. A kinematic body does not collide with other static or kinematic bodies. DYNAMIC : A dynamic body has non-zero mass, non-zero velocity determined by forces and its position is determined by the physics engine. A dynamic body can collide with other dynamic, static or kinematic bodies.

◆ ContactsPositionCorrectionTechnique

Position correction technique used in the contact solver (for contacts) BAUMGARTE_CONTACTS : Faster but can be innacurate and can lead to unexpected bounciness in some situations (due to error correction factor being added to the bodies momentum).

SPLIT_IMPULSES : A bit slower but the error correction factor is not added to the bodies momentum. This is the option used by default.

◆ JointsPositionCorrectionTechnique

Position correction technique used in the constraint solver (for joints).

BAUMGARTE_JOINTS : Faster but can be innacurate in some situations. NON_LINEAR_GAUSS_SEIDEL : Slower but more precise. This is the option used by default.

◆ TriangleRaycastSide

Raycast test side for the triangle.

Enumerator
FRONT 

Raycast against front triangle.

BACK 

Raycast against back triangle.

FRONT_AND_BACK 

Raycast against front and back triangle.