Class BulletRigidBody3D
The Bullet3DRigidBody implements Bullet rigid body for Evergine.
Inherited Members
Namespace: Evergine.Bullet
Assembly: Evergine.Bullet.dll
Syntax
public sealed class BulletRigidBody3D : BulletPhysicBody3D, IRigidBody3D, IPhysicBody3D
Constructors
BulletRigidBody3D(BulletPhysicManager3D, RigidBodyDef3D)
Initializes a new instance of the BulletRigidBody3D class.
Declaration
public BulletRigidBody3D(BulletPhysicManager3D simulation3D, RigidBodyDef3D rigidBodyDef)
Parameters
| Type | Name | Description |
|---|---|---|
| BulletPhysicManager3D | simulation3D | The bullet world. |
| RigidBodyDef3D | rigidBodyDef | The definition of Rigid body. |
Properties
Aabb
Gets the bounding box.
Declaration
public BoundingBox Aabb { get; }
Property Value
| Type | Description |
|---|---|
| BoundingBox |
ActivationState
Gets or sets the activation state.
Declaration
public ActivationState ActivationState { get; set; }
Property Value
| Type | Description |
|---|---|
| ActivationState |
AngularDamping
Gets the Angular damping is use to reduce the angular velocity.
Declaration
public float AngularDamping { get; }
Property Value
| Type | Description |
|---|---|
| float |
AngularFactor
Gets or sets the angular factor.
Declaration
public Vector3 AngularFactor { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
AngularSleepingThreshold
Gets the sleeping threshold for angular velocity.
Declaration
public float AngularSleepingThreshold { get; }
Property Value
| Type | Description |
|---|---|
| float |
AngularVelocity
Gets or sets the angular velocity.
Declaration
public Vector3 AngularVelocity { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
CenterOfMassPosition
Gets the center of mass position.
Declaration
public Vector3 CenterOfMassPosition { get; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
CenterOfMassTransform
Gets or sets the center of mass transformation.
Declaration
public Matrix4x4 CenterOfMassTransform { get; set; }
Property Value
| Type | Description |
|---|---|
| Matrix4x4 |
Gravity
Gets or sets the gravity applied to that rigid body.
Declaration
public Vector3 Gravity { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
InvInertiaDiagLocal
Gets or sets the InvInertiaDiagLocal vector of the rigid body.
Declaration
public Vector3 InvInertiaDiagLocal { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
InvInertiaTensorWorld
Gets the Inverse vector of the inertia tensor of the world.
Declaration
public Matrix4x4 InvInertiaTensorWorld { get; }
Property Value
| Type | Description |
|---|---|
| Matrix4x4 |
InvMass
Gets the inverse of the mass.
Declaration
public float InvMass { get; }
Property Value
| Type | Description |
|---|---|
| float |
IsInWorld
Gets a value indicating whether this body is in the world.
Declaration
public bool IsInWorld { get; }
Property Value
| Type | Description |
|---|---|
| bool |
IsKinematicObject
Gets a value indicating whether this body is kinematic.
Declaration
public override bool IsKinematicObject { get; }
Property Value
| Type | Description |
|---|---|
| bool |
Overrides
IsStaticObject
Gets a value indicating whether this body is static.
Declaration
public override bool IsStaticObject { get; }
Property Value
| Type | Description |
|---|---|
| bool |
Overrides
LinearDamping
Gets the Linear damping is use to reduce the linear velocity.
Declaration
public float LinearDamping { get; }
Property Value
| Type | Description |
|---|---|
| float |
LinearFactor
Gets or sets the linear factor.
Declaration
public Vector3 LinearFactor { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
LinearSleepingThreshold
Gets the sleeping threshold for linear velocity.
Declaration
public float LinearSleepingThreshold { get; }
Property Value
| Type | Description |
|---|---|
| float |
LinearVelocity
Gets or sets the linear velocity.
Declaration
public Vector3 LinearVelocity { get; set; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
LocalInertia
Gets the local inertia.
Declaration
public Vector3 LocalInertia { get; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
Mass
Gets or sets the rigid body mass.
Declaration
public float Mass { get; set; }
Property Value
| Type | Description |
|---|---|
| float |
Orientation
Gets the orientation.
Declaration
public Quaternion Orientation { get; }
Property Value
| Type | Description |
|---|---|
| Quaternion |
RigidBodyFlags
Gets or sets the rigid body flags.
Declaration
public RigidBody3DFlags RigidBodyFlags { get; set; }
Property Value
| Type | Description |
|---|---|
| RigidBody3DFlags |
TotalForce
Gets the total force applied to the rigid body.
Declaration
public Vector3 TotalForce { get; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
TotalTorque
Gets the total torque applied to the rigid body.
Declaration
public Vector3 TotalTorque { get; }
Property Value
| Type | Description |
|---|---|
| Vector3 |
Type
Gets or sets the rigid.
Declaration
public RigidBodyType3D Type { get; set; }
Property Value
| Type | Description |
|---|---|
| RigidBodyType3D |
Methods
AddColliderShape(IColliderShape3D)
Add collider shape to the body.
Declaration
public override void AddColliderShape(IColliderShape3D shape)
Parameters
| Type | Name | Description |
|---|---|---|
| IColliderShape3D | shape | The shape. |
Overrides
ApplyCentralForce(Vector3)
Apply a central force to the rigid body.
Declaration
public void ApplyCentralForce(Vector3 force)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | force | The force. |
ApplyCentralImpulse(Vector3)
Apply an impulse to the center of the rigid body.
Declaration
public void ApplyCentralImpulse(Vector3 impulse)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | impulse | The impulse. |
ApplyDamping(float)
Apply the damping.
Declaration
public void ApplyDamping(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | Delta time. |
ApplyForce(Vector3, Vector3)
Apply a force to the rigid body.
Declaration
public void ApplyForce(Vector3 force, Vector3 relativePosition)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | force | The force vector. |
| Vector3 | relativePosition | Relative poosition of the point where the force will be applied. |
ApplyGravity()
Apply the gravity.
Declaration
public void ApplyGravity()
ApplyImpulse(Vector3, Vector3)
Apply an impulse to the rigid body.
Declaration
public void ApplyImpulse(Vector3 impulse, Vector3 relativePosition)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | impulse | The impulse. |
| Vector3 | relativePosition | Relative poosition of the point where the force will be applied. |
ApplyTorque(Vector3)
Apply a torque force to the rigid body.
Declaration
public void ApplyTorque(Vector3 torque)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | torque | The torque. |
ApplyTorqueImpulse(Vector3)
Apply torque impulse to the rigid body.
Declaration
public void ApplyTorqueImpulse(Vector3 torque)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | torque | Torque impulse. |
BaseAddToWorld()
Add this body to the world simulation.
Declaration
protected override void BaseAddToWorld()
Overrides
BaseRemoveFromWorld()
Remove physic body from simulation world.
Declaration
protected override void BaseRemoveFromWorld()
Overrides
ClearForces()
Clear all forces applied to the rigid body.
Declaration
public void ClearForces()
ComputeAngularImpulseDenominator(Vector3)
Compute the angular impulse denominator.
Declaration
public float ComputeAngularImpulseDenominator(Vector3 axis)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | axis | The axis. |
Returns
| Type | Description |
|---|---|
| float | The angular impulse denominator. |
ComputeGyroscopicForceExplicit(float)
Compute the gyrocsopic forces explicit.
Declaration
public Vector3 ComputeGyroscopicForceExplicit(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | The step. |
Returns
| Type | Description |
|---|---|
| Vector3 | The Gyroscopic impulse. |
ComputeGyroscopicImpulseImplicit_Body(float)
Compute the gyrocsopic impulse implicit by Body.
Declaration
public Vector3 ComputeGyroscopicImpulseImplicit_Body(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | The step. |
Returns
| Type | Description |
|---|---|
| Vector3 | The Gyroscopic impulse. |
ComputeGyroscopicImpulseImplicit_World(float)
Compute the gyroscopic impulse implicit by world.
Declaration
public Vector3 ComputeGyroscopicImpulseImplicit_World(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | The step. |
Returns
| Type | Description |
|---|---|
| Vector3 | The Gyroscopic impulse. |
ComputeImpulseDenominator(Vector3, Vector3)
Compute impulse dominator.
Declaration
public float ComputeImpulseDenominator(Vector3 pos, Vector3 normal)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | pos | The position. |
| Vector3 | normal | The normal. |
Returns
| Type | Description |
|---|---|
| float | The impulse denominator. |
GetVelocityInLocalPoint(Vector3)
Gets the velocity in a local point of the rigid body.
Declaration
public Vector3 GetVelocityInLocalPoint(Vector3 relativePosition)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | relativePosition | The relative position. |
Returns
| Type | Description |
|---|---|
| Vector3 | The velocity in the specified point. |
InstantiateCollisionObject(PhysicBodyDef3D)
Create the rigid body.
Declaration
protected override void InstantiateCollisionObject(PhysicBodyDef3D bodyDef)
Parameters
| Type | Name | Description |
|---|---|---|
| PhysicBodyDef3D | bodyDef | The body definition. |
Overrides
IntegrateVelocities(float)
Integrate velocities.
Declaration
public void IntegrateVelocities(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | Delta time. |
RemoveColliderShape(IColliderShape3D)
Remove collider shape to the body.
Declaration
public override void RemoveColliderShape(IColliderShape3D shape)
Parameters
| Type | Name | Description |
|---|---|---|
| IColliderShape3D | shape | The shape to remove. |
Overrides
ResetMassProperty(float, Vector3)
Reset the mass property.
Declaration
public void ResetMassProperty(float mass, Vector3 inertia)
Parameters
| Type | Name | Description |
|---|---|---|
| float | mass | The mass. |
| Vector3 | inertia | The inertia. |
SetDamping(float, float)
Set Damping values.
Declaration
public void SetDamping(float linearDamping, float angularDamping)
Parameters
| Type | Name | Description |
|---|---|---|
| float | linearDamping | Linear damping value. |
| float | angularDamping | Angular damping value. |
SetSleepingThresholds(float, float)
Set sleeping threshold values.
Declaration
public void SetSleepingThresholds(float linear, float angular)
Parameters
| Type | Name | Description |
|---|---|---|
| float | linear | Linear threshold value. |
| float | angular | Angular threshold value. |
SetTransform(Vector3, Quaternion, Vector3)
Set the position of the body's origin and rotation. This breaks any contacts and wakes the other bodies. Manipulating a body's transform may cause non-physical behavior.
Declaration
public override void SetTransform(Vector3 position, Quaternion orientation, Vector3 scale)
Parameters
| Type | Name | Description |
|---|---|---|
| Vector3 | position | the world position of the body's local origin. |
| Quaternion | orientation | the world rotation as a quaternion. |
| Vector3 | scale | the world scale. |
Overrides
UpdateDeactivation(float)
Update the deactivation.
Declaration
public void UpdateDeactivation(float step)
Parameters
| Type | Name | Description |
|---|---|---|
| float | step | The time step. |
UpdateInertiaTensor()
Update the inertia tensor.
Declaration
public void UpdateInertiaTensor()
WakeUp()
Wake up the rigid body.
Declaration
public void WakeUp()
WantsSleeping()
Return if the entity need to sleep.
Declaration
public bool WantsSleeping()
Returns
| Type | Description |
|---|---|
| bool | The rigid body need to sleep. |