esp::physics::RigidBase class

Derived classes

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.
class RigidScene

Constructors, destructors, conversion operators

RigidBase(scene::SceneNode* rigidBodyNode)
~RigidBase() virtual
Virtual destructor for a RigidBase.

Public functions

auto node() -> scene::SceneNode&
Get the scene node being attached to.
auto node() const -> const scene::SceneNode&
auto object() -> scene::SceneNode&
auto object() const -> const scene::SceneNode&
auto initialize(const assets::ResourceManager& resMgr, const std::string& handle) -> bool pure virtual
Initializes the RigidObject or RigidScene that inherits from this class. This is overridden.
auto finalizeObject() -> bool pure virtual
Finalize the creation of RigidObject or RigidScene that inherits from this class.
auto setMotionType(MotionType mt) -> bool pure virtual
Set the MotionType of the object. If the object is ObjectType::SCENE it can only be MotionType::STATIC. If the object is ObjectType::OBJECT is can also be set to MotionType::KINEMATIC. Only if a dervied PhysicsManager implementing dynamics is in use can the object be set to MotionType::DYNAMIC.
auto isActive() -> bool virtual
Check whether object is being actively simulated, or sleeping. Kinematic objects are always active, but derived dynamics implementations may not be. NOTE: no active objects without a physics engine... (kinematics don't count)
void setActive() virtual
Set an object as being actively simulated rather than sleeping. Kinematic objects are always active, but derived dynamics implementations may not be.
auto getMotionType() const -> MotionType
Get the MotionType of the object. See setMotionType.
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.
void applyForce(CORRADE_UNUSED const Magnum::Vector3& force, CORRADE_UNUSED const Magnum::Vector3& relPos) virtual
Apply a force to an object through a dervied dynamics implementation. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects.
void applyImpulse(CORRADE_UNUSED const Magnum::Vector3& impulse, CORRADE_UNUSED 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 MotionType::STATIC and MotionType::KINEMATIC objects.
void applyTorque(CORRADE_UNUSED const Magnum::Vector3& torque) virtual
Apply an internal torque to an object through a dervied dynamics implementation. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects.
void applyImpulseTorque(CORRADE_UNUSED const Magnum::Vector3& impulse) virtual
Apply an internal impulse torque to an object through a dervied dynamics implementation. Does nothing for MotionType::STATIC and MotionType::KINEMATIC objects.
void setLinearVelocity(CORRADE_UNUSED const Magnum::Vector3& linVel) virtual
Virtual linear velocity setter for an object.
void setAngularVelocity(CORRADE_UNUSED const Magnum::Vector3& angVel) virtual
Virtual angular velocity setter for an object.
auto getLinearVelocity() const -> Magnum::Vector3 virtual
Virtual linear velocity getter for an object.
auto getAngularVelocity() const -> Magnum::Vector3 virtual
Virtual angular velocity getter for an object.
void setTransformation(const Magnum::Matrix4& transformation) virtual
Set the 4x4 transformation matrix of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void setTranslation(const Magnum::Vector3& vector) virtual
Set the 3D position of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void setRotation(const Magnum::Quaternion& quaternion) virtual
Set the orientation of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void setRigidState(const core::RigidState& rigidState) virtual
Set the rotation and translation of the object.
auto getRigidState() -> core::RigidState virtual
Get the rotation and translation of the object.
void resetTransformation() virtual
Reset the transformation of the object. !!NOT IMPLEMENTED!!
void translate(const Magnum::Vector3& vector) virtual
Modify the 3D position of the object kinematically by translation. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void translateLocal(const Magnum::Vector3& vector) virtual
Modify the 3D position of the object kinematically by translation with a vector defined in the object's local coordinate system. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotate(const Magnum::Rad angleInRad, const Magnum::Vector3& normalizedAxis) virtual
Modify the orientation of the object kinematically by applying an axis-angle rotation to it. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateLocal(const Magnum::Rad angleInRad, const Magnum::Vector3& normalizedAxis) virtual
Modify the orientation of the object kinematically by applying an axis-angle rotation to it in the local coordinate system. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateX(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the global X axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateY(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the global Y axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateZ(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the global Z axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateXLocal(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the local X axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateYLocal(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the local Y axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
void rotateZLocal(const Magnum::Rad angleInRad) virtual
Modify the orientation of the object kinematically by applying a rotation to it about the local Z axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.
auto getMass() const -> double virtual
Get the mass 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 getFrictionCoefficient() const -> double virtual
Get the scalar friction coefficient 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.
auto getLinearDamping() const -> double virtual
Get the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getAngularDamping() const -> double virtual
Get the scalar angular damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
auto getCOM() const -> Magnum::Vector3 virtual
Get the center of mass (COM) of the 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.
auto getInertiaMatrix() const -> Magnum::Matrix3 virtual
Get the 3x3 inertia matrix for an object.
void setMass(CORRADE_UNUSED const double mass) virtual
Set the mass of the object. Only used for dervied dynamic implementations of RigidObject.
void setCOM(CORRADE_UNUSED const Magnum::Vector3& COM) virtual
Set the center of mass (COM) of the object.
void setInertiaVector(CORRADE_UNUSED 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.
void setFrictionCoefficient(CORRADE_UNUSED const double frictionCoefficient) virtual
Set the scalar friction coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setRestitutionCoefficient(CORRADE_UNUSED const double restitutionCoefficient) virtual
Set the scalar coefficient of restitution of the object. Only used for dervied dynamic implementations of RigidObject.
void setLinearDamping(CORRADE_UNUSED const double linDamping) virtual
Set the scalar linear damping coefficient of the object. Only used for dervied dynamic implementations of RigidObject.
void setAngularDamping(CORRADE_UNUSED const double angDamping) virtual
Set the scalar angular damping coefficient for the object. Only used for dervied dynamic implementations of RigidObject.
void setSemanticId(uint32_t semanticId)
Set the esp::scene:SceneNode::semanticId_ for all visual nodes belonging to the object.
template<class T>
auto getInitializationAttributes() const -> std::shared_ptr<T>
Get a copy of the template used to initialize this object or scene.

Public variables

esp::core::Configuration attributes_
Store whatever object attributes you want here!
scene::SceneNode* BBNode_
scene::SceneNode* visualNode_
All Drawable components are children of this node.
std::vector<esp::scene::SceneNode*> visualNodes_

Protected functions

void syncPose() virtual
Used to synchronize other simulator's notion of the object state after it was changed kinematically. Called automatically on kinematic updates.

Protected variables

MotionType objectMotionType_
The MotionType of the object. Determines what operations can be performed on this object.
assets::AbstractPhysicsAttributes::ptr initializationAttributes_
Saved attributes when the object was initialized.
int objectId_
Access for the object to its own PhysicsManager id. Scene will keep -1.

Private functions

auto initialization_LibSpecific(const assets::ResourceManager& resMgr) -> bool pure virtual
Finalize the initialization of this Rigid. 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 RigidScene is created.

Function documentation

bool esp::physics::RigidBase::initialize(const assets::ResourceManager& resMgr, const std::string& handle) pure virtual

Initializes the RigidObject or RigidScene that inherits from this class. This is overridden.

Parameters
resMgr a reference to ResourceManager object
handle The handle for the template structure defining relevant phyiscal parameters for this object
Returns true if initialized successfully, false otherwise.

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

Finalize the creation of RigidObject or RigidScene that inherits from this class.

Returns whether successful finalization.

bool esp::physics::RigidBase::setMotionType(MotionType mt) pure virtual

Set the MotionType of the object. If the object is ObjectType::SCENE it can only be MotionType::STATIC. If the object is ObjectType::OBJECT is can also be set to MotionType::KINEMATIC. Only if a dervied PhysicsManager implementing dynamics is in use can the object be set to MotionType::DYNAMIC.

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

bool esp::physics::RigidBase::isActive() virtual

Check whether object is being actively simulated, or sleeping. Kinematic objects are always active, but derived dynamics implementations may not be. NOTE: no active objects without a physics engine... (kinematics don't count)

Returns true if active, false otherwise.

MotionType esp::physics::RigidBase::getMotionType() const

Get the MotionType of the object. See setMotionType.

Returns The object's current MotionType.

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

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.

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

Apply a force to an object through a dervied dynamics implementation. Does nothing for MotionType::STATIC and 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(CORRADE_UNUSED const Magnum::Vector3& impulse, CORRADE_UNUSED 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 MotionType::STATIC and 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(CORRADE_UNUSED const Magnum::Vector3& torque) virtual

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

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

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

Apply an internal impulse torque to an object through a dervied dynamics implementation. Does nothing for MotionType::STATIC and 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.

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

Virtual linear velocity setter for an object.

Parameters
linVel Linear velocity to set.

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

void esp::physics::RigidBase::setAngularVelocity(CORRADE_UNUSED 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 MotionType::KINEMATIC or MotionType::STATIC objects.

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 MotionType::KINEMATIC or MotionType::STATIC objects.

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 MotionType::KINEMATIC or MotionType::STATIC objects.

void esp::physics::RigidBase::setTransformation(const Magnum::Matrix4& transformation) virtual

Set the 4x4 transformation matrix of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
transformation The desired 4x4 transform of the object.

void esp::physics::RigidBase::setTranslation(const Magnum::Vector3& vector) virtual

Set the 3D position of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
vector The desired 3D position of the object.

void esp::physics::RigidBase::setRotation(const Magnum::Quaternion& quaternion) virtual

Set the orientation of the object kinematically. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
quaternion The desired orientation of the object.

void esp::physics::RigidBase::translate(const Magnum::Vector3& vector) virtual

Modify the 3D position of the object kinematically by translation. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
vector The desired 3D vector by which to translate the object.

void esp::physics::RigidBase::translateLocal(const Magnum::Vector3& vector) virtual

Modify the 3D position of the object kinematically by translation with a vector defined in the object's local coordinate system. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
vector The desired 3D vector in the object's ocal coordiante system by which to translate the object.

void esp::physics::RigidBase::rotate(const Magnum::Rad angleInRad, const Magnum::Vector3& normalizedAxis) virtual

Modify the orientation of the object kinematically by applying an axis-angle rotation to it. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.
normalizedAxis The desired unit vector axis of rotation.

void esp::physics::RigidBase::rotateLocal(const Magnum::Rad angleInRad, const Magnum::Vector3& normalizedAxis) virtual

Modify the orientation of the object kinematically by applying an axis-angle rotation to it in the local coordinate system. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.
normalizedAxis The desired unit vector axis of rotation in the local coordinate system.

void esp::physics::RigidBase::rotateX(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the global X axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

void esp::physics::RigidBase::rotateY(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the global Y axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

void esp::physics::RigidBase::rotateZ(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the global Z axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

void esp::physics::RigidBase::rotateXLocal(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the local X axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

void esp::physics::RigidBase::rotateYLocal(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the local Y axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

void esp::physics::RigidBase::rotateZLocal(const Magnum::Rad angleInRad) virtual

Modify the orientation of the object kinematically by applying a rotation to it about the local Z axis. Calling this during simulation of a MotionType::DYNAMIC object is not recommended.

Parameters
angleInRad The angle of rotation in radians.

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.

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

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.

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.

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.

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.

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.

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.

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.

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

Get the 3x3 inertia matrix for an object.

Returns The object's 3x3 inertia matrix.

void esp::physics::RigidBase::setMass(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setCOM(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setInertiaVector(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setFrictionCoefficient(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setRestitutionCoefficient(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setLinearDamping(CORRADE_UNUSED 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.

void esp::physics::RigidBase::setAngularDamping(CORRADE_UNUSED 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.

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.

template<class T>
std::shared_ptr<T> esp::physics::RigidBase::getInitializationAttributes() const

Get a copy of the template used to initialize this object or scene.

Returns A copy of the initialization template used to create this object instance.

bool esp::physics::RigidBase::initialization_LibSpecific(const assets::ResourceManager& resMgr) pure virtual private

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

Parameters
resMgr Reference to resource manager, to access relevant components pertaining to the object
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 RigidScene is created.

Returns whether successful finalization.

Variable documentation

scene::SceneNode* esp::physics::RigidBase::BBNode_

The SceneNode of a bounding box debug drawable. If nullptr, BB drawing is off. See toggleBBDraw().

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.

std::vector<esp::scene::SceneNode*> esp::physics::RigidBase::visualNodes_

all nodes created when this object's render asset was added to the SceneGraph