esp::physics::BulletRigidObject class

An individual rigid object instance implementing an interface with Bullet physics to enable dynamic objects. See btRigidBody for RigidObjectType::OBJECT.

Utilizes Magnum::BulletIntegration::MotionState to synchronize SceneNode state with internal btRigidBody states

Base classes

class BulletBase
This class is intended to implement bullet-specific.
class RigidObject
An AbstractFeature3D representing an individual rigid object instance attached to a SceneNode, updating its state through simulation. This may be a MotionType::STATIC scene collision geometry or an object of any MotionType which can interact with other members of a physical world. Must have a collision mesh. By default, a RigidObject is MotionType::KINEMATIC without an underlying simulator implementation. Derived classes can be used to introduce specific implementations of dynamics.

Constructors, destructors, conversion operators

BulletRigidObject(scene::SceneNode* rigidBodyNode, int objectId, std::shared_ptr<btMultiBodyDynamicsWorld> bWorld, std::shared_ptr<std::map<const btCollisionObject*, int>> collisionObjToObjIds)
Constructor for a BulletRigidObject.
~BulletRigidObject() virtual
Destructor cleans up simulation structures for the object.

Public functions

auto finalizeObject_LibSpecific() -> bool override
Finalize this object with any necessary post-creation processes.
auto buildPrimitiveCollisionObject(int primTypeVal, double halfLength) -> std::unique_ptr<btCollisionShape>
Instantiate a bullet primtive appropriate for the passed AbstractPrimitiveAttributes object.
void constructBulletCompoundFromMeshes(const Magnum::Matrix4& transformFromParentToWorld, const std::vector<assets::CollisionMeshData>& meshGroup, const assets::MeshTransformNode& node, bool join)
Recursively construct a btCompoundShape for collision from loaded mesh assets. A btConvexHullShape is constructed for each sub-component, transformed to object-local space and added to the compound in a flat manner for efficiency.
auto isActive() -> bool override
Check whether object is being actively simulated, or sleeping. See btCollisionObject::isActive.
void setActive() override
Set an object as being actively simulated rather than sleeping. See btCollisionObject::activate.
auto setMotionType(MotionType mt) -> bool override
Set the MotionType of the object. The object can be set to MotionType::STATIC, MotionType::KINEMATIC or MotionType::DYNAMIC. See btRigidBody::setCollisionFlags and btCollisionObject::CF_STATIC_OBJECT,CF_KINEMATIC_OBJECT.
void shiftOrigin(const Magnum::Vector3& shift) override
Shift the object's local origin by translating all children of this BulletRigidObject and all components of its bObjectShape_.
void applyForce(const Magnum::Vector3& force, const Magnum::Vector3& relPos) override
Apply a force to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyForce.
void applyImpulse(const Magnum::Vector3& impulse, const Magnum::Vector3& relPos) override
Apply an impulse to an object. Directly modifies the object's velocity without requiring integration through simulation. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyImpulse.
void applyTorque(const Magnum::Vector3& torque) override
Apply an internal torque to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyTorque.
void applyImpulseTorque(const Magnum::Vector3& impulse) override
Apply an internal impulse torque to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyTorqueImpulse.
auto getLinearVelocity() const -> Magnum::Vector3 override
Virtual linear velocity getter for an object.
auto getAngularVelocity() const -> Magnum::Vector3 override
Angular velocity getter for an object.
auto getMass() const -> double override
Get the mass of the object. See btRigidBody::getInvMass.
auto getCOM() const -> Magnum::Vector3 override
Get the center of mass (COM) of the object. For Bullet, COM is always the origin of the local coordinate system. See btRigidBody::getCenterOfMassPosition.
auto getInertiaVector() const -> Magnum::Vector3 override
Get the diagonal of the inertia matrix for an object. If an object is aligned with its principle axii of inertia, the 3x3 inertia matrix can be reduced to a diagonal. This is expected for Bullet. See BulletRigidObject::setInertiaVector. See btRigidBody::getInvInertiaDiagLocal.
auto getInertiaMatrix() const -> Magnum::Matrix3 override
Get the 3x3 inertia matrix for an object. For Bullet, this will be a diagonal matrix. See getInertiaVector.
auto getFrictionCoefficient() const -> double override
Get the scalar friction coefficient of the object. See btCollisionObject::getFriction.
auto getRestitutionCoefficient() const -> double override
Get the scalar coefficient of restitution of the object. See btCollisionObject::getRestitution.
auto getLinearDamping() const -> double override
Get the scalar linear damping coefficient of the object. See btRigidBody::getLinearDamping.
auto getAngularDamping() const -> double override
Get the scalar angular damping coefficient of the object. See btRigidBody::getAngularDamping.
auto getMargin() const -> double override
Get the scalar collision margin of an object. See btCompoundShape::getMargin.
void setLinearVelocity(const Magnum::Vector3& linVel) override
Linear velocity setter for an object.
void setAngularVelocity(const Magnum::Vector3& angVel) override
Angular velocity setter for an object.
void setMass(const double mass) override
Set the mass of the object. See btRigidBody::setMassProps. Note that changing mass should affect inertia, but this is not done automatically.
void setCOM(const Magnum::Vector3& COM) override
Set the center of mass (COM) of the object.
void setInertiaVector(const Magnum::Vector3& inertia) override
Set the diagonal of the inertia matrix for the object. If an object is aligned with its principle axii of inertia, the 3x3 inertia matrix can be reduced to a diagonal. This is the requirement for Bullet btRigidBody objects. See btRigidBody::setMassProps.
void setFrictionCoefficient(const double frictionCoefficient) override
Set the scalar friction coefficient of the object. See btCollisionObject::setFriction.
void setRestitutionCoefficient(const double restitutionCoefficient) override
Set the scalar coefficient of restitution of the object. See btCollisionObject::setRestitution.
void setLinearDamping(const double linearDamping) override
Set the scalar linear damping coefficient of the object. See btRigidBody::setDamping.
void setAngularDamping(const double angularDamping) override
Set the scalar angular damping coefficient for the object. See btRigidBody::setDamping.
void setMargin(const double margin) override
Set the scalar collision margin of an object. See btCompoundShape::setMargin.
void setCollisionFromBB()
Sets the object's collision shape to its bounding box. Since the bounding hierarchy is not constructed when the object is initialized, this needs to be called after loading the SceneNode.
auto isUsingBBCollisionShape() const -> bool
Public getter for usingBBCollisionShape_ set from configuration.
auto contactTest() -> bool
Return result of a discrete contact test between the object and collision world.
auto getCollisionShapeAabb() const -> const Magnum::Range3D override
Query the Aabb from bullet physics for the root compound shape of the rigid body in its local space. See btCompoundShape::getAabb.

Protected functions

void syncPose() override
Used to synchronize Bullet's notion of the object state after it was changed kinematically. Called automatically on kinematic updates. See btRigidBody::setWorldTransform.

Private functions

auto initialization_LibSpecific(const assets::ResourceManager& resMgr) -> bool override
Finalize initialization of this BulletRigidObject as a MotionType::DYNAMIC object. See btRigidBody. This holds bullet-specific functionality for objects.

Function documentation

esp::physics::BulletRigidObject::BulletRigidObject(scene::SceneNode* rigidBodyNode, int objectId, std::shared_ptr<btMultiBodyDynamicsWorld> bWorld, std::shared_ptr<std::map<const btCollisionObject*, int>> collisionObjToObjIds)

Constructor for a BulletRigidObject.

Parameters
rigidBodyNode The scene::SceneNode this feature will be attached to.
objectId
bWorld
collisionObjToObjIds

bool esp::physics::BulletRigidObject::finalizeObject_LibSpecific() override

Finalize this object with any necessary post-creation processes.

Returns whether successful finalization.

std::unique_ptr<btCollisionShape> esp::physics::BulletRigidObject::buildPrimitiveCollisionObject(int primTypeVal, double halfLength)

Instantiate a bullet primtive appropriate for the passed AbstractPrimitiveAttributes object.

Parameters
primTypeVal int value corresponding to assets::PrimObjTypes enum describing primitive collision shape.
halfLength half length of object, for primitives using this value
Returns a unique pointer to the bullet primitive object

void esp::physics::BulletRigidObject::constructBulletCompoundFromMeshes(const Magnum::Matrix4& transformFromParentToWorld, const std::vector<assets::CollisionMeshData>& meshGroup, const assets::MeshTransformNode& node, bool join)

Recursively construct a btCompoundShape for collision from loaded mesh assets. A btConvexHullShape is constructed for each sub-component, transformed to object-local space and added to the compound in a flat manner for efficiency.

Parameters
transformFromParentToWorld The cumulative parent-to-world transformation matrix constructed by composition down the MeshTransformNode tree to the current node.
meshGroup Access structure for collision mesh data.
node The current MeshTransformNode in the recursion.
join Whether or not to join sub-meshes into a single con convex shape, rather than creating individual convexes under the compound.

bool esp::physics::BulletRigidObject::isActive() override

Check whether object is being actively simulated, or sleeping. See btCollisionObject::isActive.

Returns true if active, false otherwise.

bool esp::physics::BulletRigidObject::setMotionType(MotionType mt) override

Set the MotionType of the object. The object can be set to MotionType::STATIC, MotionType::KINEMATIC or MotionType::DYNAMIC. See btRigidBody::setCollisionFlags and btCollisionObject::CF_STATIC_OBJECT,CF_KINEMATIC_OBJECT.

Parameters
mt The desirved MotionType.
Returns true if successfully set, false otherwise.

void esp::physics::BulletRigidObject::shiftOrigin(const Magnum::Vector3& shift) override

Shift the object's local origin by translating all children of this BulletRigidObject and all components of its bObjectShape_.

Parameters
shift The translation to apply.

void esp::physics::BulletRigidObject::applyForce(const Magnum::Vector3& force, const Magnum::Vector3& relPos) override

Apply a force to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyForce.

Parameters
force The desired linear force on the object in the global coordinate system.
relPos The desired location of force application in the global coordinate system relative to the object's center of mass.

void esp::physics::BulletRigidObject::applyImpulse(const Magnum::Vector3& impulse, const Magnum::Vector3& relPos) override

Apply an impulse to an object. Directly modifies the object's velocity without requiring integration through simulation. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyImpulse.

Parameters
impulse The desired impulse on the object in the global coordinate system.
relPos The desired location of impulse application in the global coordinate system relative to the object's center of mass.

void esp::physics::BulletRigidObject::applyTorque(const Magnum::Vector3& torque) override

Apply an internal torque to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyTorque.

Parameters
torque The desired torque on the object in the local coordinate system.

void esp::physics::BulletRigidObject::applyImpulseTorque(const Magnum::Vector3& impulse) override

Apply an internal impulse torque to an object. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects. Calls setActive(). See btRigidBody::applyTorqueImpulse.

Parameters
impulse The desired impulse torque on the object in the local coordinate system. Directly modifies the object's angular velocity without requiring integration through simulation.

Magnum::Vector3 esp::physics::BulletRigidObject::getLinearVelocity() const override

Virtual linear velocity getter for an object.

Returns Linear velocity of the object.

Magnum::Vector3 esp::physics::BulletRigidObject::getAngularVelocity() const override

Angular velocity getter for an object.

Returns Angular velocity vector corresponding to world unit axis angles.

double esp::physics::BulletRigidObject::getMass() const override

Get the mass of the object. See btRigidBody::getInvMass.

Returns The mass of the object.

Magnum::Vector3 esp::physics::BulletRigidObject::getCOM() const override

Get the center of mass (COM) of the object. For Bullet, COM is always the origin of the local coordinate system. See btRigidBody::getCenterOfMassPosition.

Returns Object 3D center of mass in the global coordinate system.

Magnum::Vector3 esp::physics::BulletRigidObject::getInertiaVector() const override

Get the diagonal of the inertia matrix for an object. If an object is aligned with its principle axii of inertia, the 3x3 inertia matrix can be reduced to a diagonal. This is expected for Bullet. See BulletRigidObject::setInertiaVector. See btRigidBody::getInvInertiaDiagLocal.

Returns The diagonal of the object's inertia matrix.

Magnum::Matrix3 esp::physics::BulletRigidObject::getInertiaMatrix() const override

Get the 3x3 inertia matrix for an object. For Bullet, this will be a diagonal matrix. See getInertiaVector.

Returns The object's 3x3 inertia matrix.

double esp::physics::BulletRigidObject::getFrictionCoefficient() const override

Get the scalar friction coefficient of the object. See btCollisionObject::getFriction.

Returns The scalar friction coefficient of the object.

double esp::physics::BulletRigidObject::getRestitutionCoefficient() const override

Get the scalar coefficient of restitution of the object. See btCollisionObject::getRestitution.

Returns The scalar coefficient of restitution of the object.

double esp::physics::BulletRigidObject::getLinearDamping() const override

Get the scalar linear damping coefficient of the object. See btRigidBody::getLinearDamping.

Returns The scalar linear damping coefficient of the object.

double esp::physics::BulletRigidObject::getAngularDamping() const override

Get the scalar angular damping coefficient of the object. See btRigidBody::getAngularDamping.

Returns The scalar angular damping coefficient of the object.

double esp::physics::BulletRigidObject::getMargin() const override

Get the scalar collision margin of an object. See btCompoundShape::getMargin.

Returns The scalar collision margin of the object.

void esp::physics::BulletRigidObject::setLinearVelocity(const Magnum::Vector3& linVel) override

Linear velocity setter for an object.

Parameters
linVel Linear velocity to set.

Does nothing for MotionType::KINEMATIC or MotionType::STATIC objects. Sets internal btRigidObject state. Treated as initial velocity during simulation simulation step.

void esp::physics::BulletRigidObject::setAngularVelocity(const Magnum::Vector3& angVel) override

Angular velocity setter for an object.

Parameters
angVel Angular velocity vector corresponding to world unit axis angles.

Does nothing for MotionType::KINEMATIC or MotionType::STATIC objects. Sets internal btRigidObject state. Treated as initial velocity during simulation simulation step.

void esp::physics::BulletRigidObject::setMass(const double mass) override

Set the mass of the object. See btRigidBody::setMassProps. Note that changing mass should affect inertia, but this is not done automatically.

Parameters
mass The new mass of the object.

void esp::physics::BulletRigidObject::setCOM(const Magnum::Vector3& COM) override

Set the center of mass (COM) of the object.

Parameters
COM Object 3D center of mass in the local coordinate system. !!! Currently not supported !!! All Bullet btRigidBody objects must have a COM located at their local origins.

void esp::physics::BulletRigidObject::setInertiaVector(const Magnum::Vector3& inertia) override

Set the diagonal of the inertia matrix for the object. If an object is aligned with its principle axii of inertia, the 3x3 inertia matrix can be reduced to a diagonal. This is the requirement for Bullet btRigidBody objects. See btRigidBody::setMassProps.

Parameters
inertia The new diagonal for the object's inertia matrix.

void esp::physics::BulletRigidObject::setFrictionCoefficient(const double frictionCoefficient) override

Set the scalar friction coefficient of the object. See btCollisionObject::setFriction.

Parameters
frictionCoefficient The new scalar friction coefficient of the object.

void esp::physics::BulletRigidObject::setRestitutionCoefficient(const double restitutionCoefficient) override

Set the scalar coefficient of restitution of the object. See btCollisionObject::setRestitution.

Parameters
restitutionCoefficient The new scalar coefficient of restitution of the object.

void esp::physics::BulletRigidObject::setLinearDamping(const double linearDamping) override

Set the scalar linear damping coefficient of the object. See btRigidBody::setDamping.

Parameters
linearDamping The new scalar linear damping coefficient of the object.

void esp::physics::BulletRigidObject::setAngularDamping(const double angularDamping) override

Set the scalar angular damping coefficient for the object. See btRigidBody::setDamping.

Parameters
angularDamping The new scalar angular damping coefficient for the object.

void esp::physics::BulletRigidObject::setMargin(const double margin) override

Set the scalar collision margin of an object. See btCompoundShape::setMargin.

Parameters
margin The new scalar collision margin of the object.

bool esp::physics::BulletRigidObject::isUsingBBCollisionShape() const

Public getter for usingBBCollisionShape_ set from configuration.

Returns usingBBCollisionShape_ is true if "useBoundingBoxForCollision" was set in object's configuration.

bool esp::physics::BulletRigidObject::contactTest()

Return result of a discrete contact test between the object and collision world.

Returns Whether or not the object is in contact with any other collision enabled objects.

See SimulationContactResultCallback

const Magnum::Range3D esp::physics::BulletRigidObject::getCollisionShapeAabb() const override

Query the Aabb from bullet physics for the root compound shape of the rigid body in its local space. See btCompoundShape::getAabb.

Returns The Aabb.

bool esp::physics::BulletRigidObject::initialization_LibSpecific(const assets::ResourceManager& resMgr) override private

Finalize initialization of this BulletRigidObject as a MotionType::DYNAMIC object. See btRigidBody. This holds bullet-specific functionality for objects.

Parameters
resMgr Reference to resource manager, to access relevant components pertaining to the scene object
Returns true if initialized successfully, false otherwise.