esp::physics::RigidBase class

This class specifies the functionality expected of rigid objects and stages, particularly with regard to dynamic simulation, if such a library, such as bullet, is available.

Base classes

class PhysicsObjectBase

Derived classes

class ArticulatedLink
A single rigid link in a kinematic chain. Abstract class. Feature attaches to a SceneNode.
class RigidObject
A RigidBase representing an individual rigid object instance attached to a SceneNode, updating its state through simulation. This may be a esp::physics::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.
class RigidStage
A RigidBase representing an individual rigid stage instance attached to a SceneNode. This construction currently may only be esp::physics::MotionType::STATIC.

Constructors, destructors, conversion operators

RigidBase(scene::SceneNode* rigidBodyNode, int objectId, const assets::ResourceManager& resMgr)
Constructor for a RigidBase.
~RigidBase() defaulted override
Virtual destructor for a RigidBase.

Public functions

auto initialize(std::shared_ptr<metadata::attributes::AbstractObjectAttributes> initAttributes) -> bool pure virtual
Initializes the RigidObject or esp::physics::RigidStage that inherits from this class. This is overridden.
auto finalizeObject() -> bool pure virtual
Finalize the creation of RigidObject or esp::physics::RigidStage that inherits from this class.
auto getCollidable() const -> bool
void setCollidable(bool collidable) virtual
Set a rigid as collidable or not. Derived implementations handle the specifics of modifying the collision properties.
void applyForce(const Magnum::Vector3& force, const Magnum::Vector3& relPos) virtual
Apply a force to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.
void applyImpulse(const Magnum::Vector3& impulse, const Magnum::Vector3& relPos) virtual
Apply an impulse to an object through a dervied dynamics implementation. Directly modifies the object's velocity without requiring integration through simulation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.
void applyTorque(const Magnum::Vector3& torque) virtual
Apply an internal torque to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.
void applyImpulseTorque(const Magnum::Vector3& impulse) virtual
Apply an internal impulse torque to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.
auto getAngularDamping() const -> double virtual
Get the scalar angular damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setAngularDamping(const double angDamping) virtual
Set the scalar angular damping coefficient for the object. Only used for dervied dynamic implementations of RigidObject.
auto getAngularVelocity() const -> Magnum::Vector3 virtual
Virtual angular velocity getter for an object.
void setAngularVelocity(const Magnum::Vector3& angVel) virtual
Virtual angular velocity setter for an object.
auto getCOM() const -> Magnum::Vector3 virtual
Get the center of mass (COM) of the object.
void setCOM(const Magnum::Vector3& COM) virtual
Set the center of mass (COM) of the object.
auto getFrictionCoefficient() const -> double virtual
Get the scalar friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setFrictionCoefficient(const double frictionCoefficient) virtual
Set the scalar friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getRollingFrictionCoefficient() const -> double virtual
Get the scalar rolling friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setRollingFrictionCoefficient(const double rollingFrictionCoefficient) virtual
Set the scalar rolling friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getSpinningFrictionCoefficient() const -> double virtual
Get the scalar spinning friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setSpinningFrictionCoefficient(const double spinningFrictionCoefficient) virtual
Set the scalar spinning friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getInertiaMatrix() const -> Magnum::Matrix3 virtual
Get the 3x3 inertia matrix for an object.
auto getInertiaVector() const -> Magnum::Vector3 virtual
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. See RigidObject::setInertiaVector.
void setInertiaVector(const Magnum::Vector3& inertia) virtual
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.
auto getInitObjectInstanceAttr() const -> std::shared_ptr<const metadata::attributes::SceneObjectInstanceAttributes>
Returns the metadata::attributes::SceneObjectInstanceAttributes used to place this rigid object in the scene.
auto getCurrentStateInstanceAttr() -> std::shared_ptr<metadata::attributes::SceneObjectInstanceAttributes>
Return a metadata::attributes::SceneObjectInstanceAttributes reflecting the current state of this Rigid.
auto getLinearDamping() const -> double virtual
Get the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setLinearDamping(const double linDamping) virtual
Set the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getLinearVelocity() const -> Magnum::Vector3 virtual
Virtual linear velocity getter for an object.
void setLinearVelocity(const Magnum::Vector3& linVel) virtual
Virtual linear velocity setter for an object.
auto getMass() const -> double virtual
Get the mass of the object. Only used for dervied dynamic implementations of RigidObject.
void setMass(const double mass) virtual
Set the mass of the object. Only used for dervied dynamic implementations of RigidObject.
auto getRestitutionCoefficient() const -> double virtual
Get the scalar coefficient of restitution of the object. Only used for dervied dynamic implementations of RigidObject.
void setRestitutionCoefficient(const double restitutionCoefficient) virtual
Set the scalar coefficient of restitution of the object. Only used for dervied dynamic implementations of RigidObject.
auto getScale() const -> Magnum::Vector3 virtual
Get the scale of the object set during initialization.
auto getSemanticId() const -> int
Get the semantic ID for this object.
void setSemanticId(uint32_t semanticId)
Set the esp::scene::SceneNode::semanticId_ for all visual nodes belonging to the object.
auto getVisualSceneNodes() const -> std::vector<scene::SceneNode*> override
Get pointers to this rigid's visual SceneNodes.

Public variables

scene::SceneNode* BBNode_
The SceneNode of a bounding box debug drawable. If nullptr, BB drawing is off. See setObjectBBDraw().
scene::SceneNode* visualNode_
All Drawable components are children of this node.
std::vector<esp::scene::SceneNode*> visualNodes_
all nodes created when this object's render asset was added to the SceneGraph

Protected functions

void shiftOrigin(const Magnum::Vector3& shift) virtual
Shift the object's local origin by translating all children of this object's SceneNode.
void shiftOriginToBBCenter()
Shift the object's local origin to be coincident with the center of it's bounding box, cumulativeBB_. See shiftOrigin.

Protected variables

bool isCollidable_
Flag sepcifying whether or not the object has an active collision shape.

Private functions

auto initialization_LibSpecific() -> bool pure virtual
Finalize the initialization of this RigidBase. This is overridden by inheriting objects.
auto finalizeObject_LibSpecific() -> bool pure virtual
any physics-lib-specific finalization code that needs to be run after RigidObject or RigidStage is created.

Function documentation

esp::physics::RigidBase::RigidBase(scene::SceneNode* rigidBodyNode, int objectId, const assets::ResourceManager& resMgr)

Constructor for a RigidBase.

Parameters
rigidBodyNode Pointer to the node to be used for this rigid.
objectId the desired ID for this rigid construct.
resMgr a reference to esp::assets::ResourceManager

bool esp::physics::RigidBase::initialize(std::shared_ptr<metadata::attributes::AbstractObjectAttributes> initAttributes) pure virtual

Initializes the RigidObject or esp::physics::RigidStage that inherits from this class. This is overridden.

Parameters
initAttributes The template structure defining relevant physical parameters for this object
Returns true if initialized successfully, false otherwise.

bool esp::physics::RigidBase::finalizeObject() pure virtual

Finalize the creation of RigidObject or esp::physics::RigidStage that inherits from this class.

Returns whether successful finalization.

void esp::physics::RigidBase::applyForce(const Magnum::Vector3& force, const Magnum::Vector3& relPos) virtual

Apply a force to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.

Parameters
force The desired 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::RigidBase::applyImpulse(const Magnum::Vector3& impulse, const Magnum::Vector3& relPos) virtual

Apply an impulse to an object through a dervied dynamics implementation. Directly modifies the object's velocity without requiring integration through simulation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.

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::RigidBase::applyTorque(const Magnum::Vector3& torque) virtual

Apply an internal torque to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.

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

void esp::physics::RigidBase::applyImpulseTorque(const Magnum::Vector3& impulse) virtual

Apply an internal impulse torque to an object through a dervied dynamics implementation. Does nothing for esp::physics::MotionType::STATIC and esp::physics::MotionType::KINEMATIC objects.

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.

double esp::physics::RigidBase::getAngularDamping() const virtual

Get the scalar angular damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar angular damping coefficient of the object.

For kinematic objects they are dummies, for dynamic objects implemented in physics-engine specific ways

void esp::physics::RigidBase::setAngularDamping(const double angDamping) virtual

Set the scalar angular damping coefficient for the object. Only used for dervied dynamic implementations of RigidObject.

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

Magnum::Vector3 esp::physics::RigidBase::getAngularVelocity() const virtual

Virtual angular velocity getter for an object.

Returns Angular velocity vector corresponding to world unit axis angles.

Returns zero for default esp::physics::MotionType::KINEMATIC or esp::physics::MotionType::STATIC objects.

void esp::physics::RigidBase::setAngularVelocity(const Magnum::Vector3& angVel) virtual

Virtual angular velocity setter for an object.

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

Does nothing for default esp::physics::MotionType::KINEMATIC or esp::physics::MotionType::STATIC objects.

Magnum::Vector3 esp::physics::RigidBase::getCOM() const virtual

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

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

void esp::physics::RigidBase::setCOM(const Magnum::Vector3& COM) virtual

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

Parameters
COM Object 3D center of mass in the local coordinate system.

double esp::physics::RigidBase::getFrictionCoefficient() const virtual

Get the scalar friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar friction coefficient of the object.

void esp::physics::RigidBase::setFrictionCoefficient(const double frictionCoefficient) virtual

Set the scalar friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Parameters
frictionCoefficient The new scalar friction coefficient of the object.

double esp::physics::RigidBase::getRollingFrictionCoefficient() const virtual

Get the scalar rolling friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar rolling friction coefficient of the object. Damps angular velocity about axis orthogonal to the contact normal to prevent rounded shapes from rolling forever.

void esp::physics::RigidBase::setRollingFrictionCoefficient(const double rollingFrictionCoefficient) virtual

Set the scalar rolling friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Parameters
rollingFrictionCoefficient The new scalar rolling friction coefficient of the object. Damps angular velocity about axis orthogonal to the contact normal to prevent rounded shapes from rolling forever.

double esp::physics::RigidBase::getSpinningFrictionCoefficient() const virtual

Get the scalar spinning friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar spinning friction coefficient of the object. Damps angular velocity about the contact normal.

void esp::physics::RigidBase::setSpinningFrictionCoefficient(const double spinningFrictionCoefficient) virtual

Set the scalar spinning friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Parameters
spinningFrictionCoefficient The new scalar friction coefficient of the object. Damps angular velocity about the contact normal.

Magnum::Matrix3 esp::physics::RigidBase::getInertiaMatrix() const virtual

Get the 3x3 inertia matrix for an object.

Returns The object's 3x3 inertia matrix.

Magnum::Vector3 esp::physics::RigidBase::getInertiaVector() const virtual

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. See RigidObject::setInertiaVector.

Returns The diagonal of the object's inertia matrix.

void esp::physics::RigidBase::setInertiaVector(const Magnum::Vector3& inertia) virtual

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.

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

std::shared_ptr<const metadata::attributes::SceneObjectInstanceAttributes> esp::physics::RigidBase::getInitObjectInstanceAttr() const

Returns the metadata::attributes::SceneObjectInstanceAttributes used to place this rigid object in the scene.

Returns a read-only copy of the metadata::attributes::SceneInstanceAttributes used to place this object in the scene.

double esp::physics::RigidBase::getLinearDamping() const virtual

Get the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar linear damping coefficient of the object.

void esp::physics::RigidBase::setLinearDamping(const double linDamping) virtual

Set the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.

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

Magnum::Vector3 esp::physics::RigidBase::getLinearVelocity() const virtual

Virtual linear velocity getter for an object.

Returns Linear velocity of the object.

Returns zero for default esp::physics::MotionType::KINEMATIC or esp::physics::MotionType::STATIC objects.

void esp::physics::RigidBase::setLinearVelocity(const Magnum::Vector3& linVel) virtual

Virtual linear velocity setter for an object.

Parameters
linVel Linear velocity to set.

Does nothing for default esp::physics::MotionType::KINEMATIC or esp::physics::MotionType::STATIC objects.

double esp::physics::RigidBase::getMass() const virtual

Get the mass of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The mass of the object.

void esp::physics::RigidBase::setMass(const double mass) virtual

Set the mass of the object. Only used for dervied dynamic implementations of RigidObject.

Parameters
mass The new mass of the object.

double esp::physics::RigidBase::getRestitutionCoefficient() const virtual

Get the scalar coefficient of restitution of the object. Only used for dervied dynamic implementations of RigidObject.

Returns The scalar coefficient of restitution of the object.

void esp::physics::RigidBase::setRestitutionCoefficient(const double restitutionCoefficient) virtual

Set the scalar coefficient of restitution of the object. Only used for dervied dynamic implementations of RigidObject.

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

Magnum::Vector3 esp::physics::RigidBase::getScale() const virtual

Get the scale of the object set during initialization.

Returns The scaling for the object relative to its initially loaded meshes.

void esp::physics::RigidBase::setSemanticId(uint32_t semanticId)

Set the esp::scene::SceneNode::semanticId_ for all visual nodes belonging to the object.

Parameters
semanticId The desired semantic id for the object.

std::vector<scene::SceneNode*> esp::physics::RigidBase::getVisualSceneNodes() const override

Get pointers to this rigid's visual SceneNodes.

Returns vector of pointers to the rigid's visual scene nodes.

void esp::physics::RigidBase::shiftOrigin(const Magnum::Vector3& shift) virtual protected

Shift the object's local origin by translating all children of this object's SceneNode.

Parameters
shift The translation to apply to object's children.

bool esp::physics::RigidBase::initialization_LibSpecific() pure virtual private

Finalize the initialization of this RigidBase. This is overridden by inheriting objects.

Returns true if initialized successfully, false otherwise.

bool esp::physics::RigidBase::finalizeObject_LibSpecific() pure virtual private

any physics-lib-specific finalization code that needs to be run after RigidObject or RigidStage is created.

Returns whether successful finalization.

Variable documentation

scene::SceneNode* esp::physics::RigidBase::visualNode_

All Drawable components are children of this node.

Note that the transformation of this node is a composition of rotation and translation as scaling is applied to a child of this node.