esp::physics::PhysicsManager class

Kinematic and dynamic scene and object manager. Responsible for tracking, updating, and synchronizing the state of the physical world and all non-static geometry in the scene as well as interfacing with specific physical simulation implementations.

The physical world in this case consists of any objects which can be manipulated:addObject : (kinematically or dynamically) or simulated and anything such objects must be aware of (e.g. static scene collision geometry).

May eventually manage multiple physical scenes, but currently assumes only one unique physical world can exist.

Derived classes

class BulletPhysicsManager
Dynamic stage and object manager interfacing with Bullet physics engine: https://github.com/bulletphysics/bullet3.

Public types

enum class PhysicsSimulationLibrary { NoPhysics, Bullet }
==== physics engines ====
using DrawableGroup = gfx::DrawableGroup
Stores references to a set of drawable elements.

Constructors, destructors, conversion operators

PhysicsManager(assets::ResourceManager& _resourceManager, const std::shared_ptr<const metadata::attributes::PhysicsManagerAttributes>& _physicsManagerAttributes) explicit
Construct a ref PhysicsManager with access to specific resource assets.
~PhysicsManager() virtual
Destructor.

Public functions

void setSimulator(esp::sim::Simulator* _simulator)
Set a pointer to this physics manager's owning simulator.
auto initPhysics(scene::SceneNode* node) -> bool
Initialization: load physical properties and setup the world.
void reset() virtual
Reset the simulation and physical world. Sets the worldTime_ to 0.0, does not change physical state.
auto addStageInstance(const metadata::attributes::StageAttributes::ptr& initAttributes, const metadata::attributes::SceneObjectInstanceAttributes::cptr& stageInstanceAttributes) -> bool
Initialize static scene collision geometry from loaded mesh data. Only one 'scene' may be initialized per simulated world, but this scene may contain several components (e.g. GLB hierarchy).
auto addObjectInstance(const esp::metadata::attributes::SceneObjectInstanceAttributes::cptr& objInstAttributes, const std::string& attributesHandle, bool defaultCOMCorrection = false, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance and place a physics object from a esp::metadata::attributes::SceneObjectInstanceAttributes file.
auto addObject(const std::string& attributesHandle, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance a physical object from an object properties template in the esp::metadata::managers::ObjectAttributesManager. This method will query for a drawable group from simulator.
auto addObject(int attributesID, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance a physical object from an object properties template in the esp::metadata::managers::ObjectAttributesManager by template ID. This method will query for a drawable group from simulator.
auto getRigidObjectWrapper() -> ManagedRigidObject::ptr virtual
Create an object wrapper appropriate for this physics manager. Overridden if called by dynamics-library-enabled PhysicsManager.
void removeObject(int objectId, bool deleteObjectNode = true, bool deleteVisualNode = true) virtual
Remove an object instance from the pysical scene by ID, destroying its scene graph node and removing it from PhysicsManager::existingObjects_.
auto getNumRigidObjects() const -> int
Get the number of objects mapped in PhysicsManager::existingObjects_.
auto getExistingObjectIDs() const -> std::vector<int>
Get a list of existing object IDs (i.e., existing keys in PhysicsManager::existingObjects_.)
auto addArticulatedObjectInstance(const std::shared_ptr<const esp::metadata::attributes::SceneAOInstanceAttributes>& aObjInstAttributes, const std::string& attributesHandle, DrawableGroup* drawables = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance and place an ArticulatedObject from a esp::metadata::attributes::SceneAOInstanceAttributes file.
auto addArticulatedObject(const std::string& attributesHandle, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance an ArticulatedObject from an esp::metadata::attributes::ArticulatedObjectAttributes retrieved from the esp::metadata::managers::AOAttributesManager by the given attributesHandle .
auto addArticulatedObject(int attributesID, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance an ArticulatedObject from an esp::metadata::attributes::ArticulatedObjectAttributes retrieved from the esp::metadata::managers::AOAttributesManager by the given attributesID .
auto addArticulatedObjectFromURDF(const std::string& filepath, DrawableGroup* drawables = nullptr, bool fixedBase = false, float globalScale = 1.0, float massScale = 1.0, bool forceReload = false, bool maintainLinkOrder = false, bool intertiaFromURDF = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Load, parse, and import a URDF file instantiating an ArticulatedObject in the world.
void removeArticulatedObject(int objectId) virtual
Remove an ArticulatedObject from the world by unique id.
auto getNumArticulatedObjects() -> int
Get the current number of instanced articulated objects in the world.
auto getArticulatedObject(int objectId) -> ArticulatedObject&
auto getArticulatedObjectWrapper() -> ManagedArticulatedObject::ptr virtual
Create an articulated object wrapper appropriate for this physics manager. Overridden if called by dynamics-library-enabled PhysicsManager.
auto getExistingArticulatedObjectIds() const -> std::vector<int>
Get a list of existing object IDs for articulated objects (i.e., existing keys in PhysicsManager::existingArticulatedObjects_.)
void stepPhysics(double dt = 0.0) virtual
Step the physical world forward in time. Time may only advance in increments of fixedTimeStep_.
void deferNodesUpdate() virtual
Defers the update of the scene graph nodes until updateNodes is called This is needed to do ownership transfer of the scene graph to a background thread.
void updateNodes() virtual
Syncs the state of physics simulation to the rendering scene graph.
void setTimestep(double dt) virtual
Set the fixedTimeStep_ of the physical world. See stepPhysics.
void setGravity(const Magnum::Vector3& gravity) virtual
Set the gravity of the physical world if the world is dyanmic and therefore has a notion of force. By default does nothing since the world is kinematic. Exact implementations of gravity will depend on the specific dynamics of the derived physical simulator class.
auto getTimestep() const -> double virtual
Get the fixedTimeStep_ of the physical world. See stepPhysics.
auto getWorldTime() const -> double virtual
Get the current worldTime_ of the physical world. See stepPhysics.
auto getGravity() const -> Magnum::Vector3 virtual
Get the current gravity in the physical world. By default returns [0,0,0] since their is no notion of force in a kinematic world.
auto getStageFrictionCoefficient() const -> double virtual
Get the current friction coefficient of the scene collision geometry. See staticStageObject_.
void setStageFrictionCoefficient(const double frictionCoefficient) virtual
Set the friction coefficient of the scene collision geometry. See staticStageObject_.
auto getStageRestitutionCoefficient() const -> double virtual
Get the current coefficient of restitution for the scene collision geometry. This determines the ratio of initial to final relative velocity between the scene and collidiing object. See staticStageObject_. By default this will always return 0, since kinametic scenes have no dynamics.
void setStageRestitutionCoefficient(const double restitutionCoefficient) virtual
Set the coefficient of restitution for the scene collision geometry. See staticStageObject_. By default does nothing since kinametic scenes have no dynamics.
auto checkActiveObjects() -> int
Get the number of objects in PhysicsManager::existingObjects_ considered active by the physics simulator currently in use. See RigidObject::isActive.
void setObjectBBDraw(int physObjectID, DrawableGroup* drawables, bool drawBB)
Set bounding box rendering for the object true or false.
auto getObjectVisualSceneNode(int physObjectID) const -> const scene::SceneNode&
Get the root node of an object's visual SceneNode subtree.
void debugDraw(const Magnum::Matrix4& projTrans) const virtual
Render any debugging visualizations provided by the underlying physics simulator implementation. By default does nothing. See BulletPhysicsManager::debugDraw.
auto contactTest(const int physObjectID) -> bool virtual
Check whether an object is in contact with any other objects or the scene.
void performDiscreteCollisionDetection() virtual
Perform discrete collision detection for the scene with the derived PhysicsManager implementation. Not implemented for default PhysicsManager. See BulletPhysicsManager.
auto getNumActiveContactPoints() -> int virtual
Query the number of contact points that were active during the most recent collision detection check.
auto getNumActiveOverlappingPairs() -> int virtual
See BulletPhysicsManager.h getNumActiveOverlappingPairs.
auto getStepCollisionSummary() -> std::string virtual
See BulletPhysicsManager.h getStepCollisionSummary.
auto getContactPoints() const -> std::vector<ContactPointData> virtual
Query physics simulation implementation for contact point data from the most recent collision detection cache.
void setStageIsCollidable(bool collidable)
Set the stage to collidable or not.
auto getStageIsCollidable() -> bool
Get whether or not the stage is collision active.
auto getPhysicsSimulationLibrary() const -> const PhysicsSimulationLibrary&
Return the library implementation type for the simulator currently in use. Use to check for a particular implementation.
auto getStageInitAttributes() const -> metadata::attributes::StageAttributes::ptr
Get a copy of the template used to initialize the stage.
auto getInitializationAttributes() const -> std::shared_ptr<metadata::attributes::PhysicsManagerAttributes>
Get a copy of the template used to initialize this physics manager.
auto castRay(const esp::geo::Ray& ray, double maxDistance = 100.0) -> RaycastResults virtual
Cast a ray into the collision world and return a RaycastResults with hit information.
auto getRigidObjectManager() const -> std::shared_ptr<RigidObjectManager>
returns the wrapper manager for the currently created rigid objects.
auto getArticulatedObjectManager() -> std::shared_ptr<ArticulatedObjectManager>
returns the wrapper manager for the currently created articulated objects.
auto isValidRigidObjectId(const int physObjectID) const -> bool
Check if physObjectID represents an existing rigid object.
auto isValidArticulatedObjectId(const int physObjectID) const -> bool
Check if physObjectID represents an existing articulated object.
auto createRigidConstraint(const RigidConstraintSettings& settings) -> int virtual
Create a rigid constraint between two objects or an object and the world.
void updateRigidConstraint(int constraintId, const RigidConstraintSettings& settings) virtual
Update the settings of a rigid constraint.
void removeRigidConstraint(int constraintId) virtual
Remove a rigid constraint by id.
auto getRigidConstraintSettings(int constraintId) const -> RigidConstraintSettings
Get a copy of the settings for an existing rigid constraint.
void buildCurrentStateSceneAttributes(const metadata::attributes::SceneInstanceAttributes::ptr& sceneInstanceAttrs) const
This will populate the passed sceneInstanceAttrs with the current stage, object and articulated object instances reflecting the current state of the physics world.
auto addTrajectoryObject(const std::string& trajVisName, const std::vector<Mn::Vector3>& pts, const std::vector<Mn::Color3>& colorVec, int numSegments = 3, float radius = .001, bool smooth = false, int numInterp = 10, DrawableGroup* drawables = nullptr) -> int
Compute a trajectory visualization for the passed points.
auto removeTrajVisByName(const std::string& trajVisName) -> bool
Remove a trajectory visualization by name.
auto removeTrajVisByID(int trajVisObjID) -> bool
Remove a trajectory visualization by object ID.

Protected functions

auto addObjectAndSaveAttributes(const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY, bool defaultCOMCorrection = false, esp::metadata::attributes::SceneObjectInstanceAttributes::cptr objInstAttributes = nullptr) -> int
This method will create a physical object using the passed values by calling addObjectInternal, will initialize its state and save it's instantiation attributes.
auto addObjectInternal(const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, DrawableGroup* drawables, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int
Instance a physical object from an ObjectAttributes template.
auto addArticulatedObjectAndSaveAttributes(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY, esp::metadata::attributes::SceneAOInstanceAttributes::cptr artObjInstAttributes = nullptr) -> int
This method will create a physical object using the passed values by calling addArticulatedObjectInternal, will initialize its state and save it's instantiation attributes.
auto addArticulatedObjectInternal(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes, DrawableGroup* drawables, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) -> int virtual
Load, parse, and import a URDF file instantiating an ArticulatedObject in the world based on the urdf filepath specified in esp::metadata::attributes::ArticulatedObjectAttributes. This version requires drawables to be provided.
auto removeTrajVisObjectAndAssets(int trajVisObjID, const std::string& trajVisName) -> bool
Internal use only. Remove a trajectory object, its mesh, and all references to it.
auto getRigidObjIteratorOrAssert(const int physObjectID) -> std::map<int, RigidObject::ptr>::iterator
Retrieve an iterator to a given object ID's value if it is valid (i.e. it refers to an existing rigid object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.
auto getArticulatedObjIteratorOrAssert(const int physObjectID) -> std::map<int, ArticulatedObject::ptr>::iterator
Retrieve an iterator to a given articulated object ID's value if it is valid (i.e. it refers to an existing articulated object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.
auto getConstRigidObjIteratorOrAssert(const int physObjectID) const -> std::map<int, RigidObject::ptr>::const_iterator
Retrieve an iterator to a given object ID's value if it is valid (i.e. it refers to an existing rigid object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.
auto getConstArticulatedObjIteratorOrAssert(const int physObjectID) const -> std::map<int, ArticulatedObject::ptr>::const_iterator
Retrieve an iterator to a given articulated object ID's value if it is valid (i.e. it refers to an existing articulated object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.
auto allocateObjectID() -> int
Acquire a new ObjectID by recycling the ID of an object removed with removeObject or by incrementing nextObjectID_. See addObject.
auto deallocateObjectID(int physObjectID) -> int
Recycle the ID of an object removed with removeObject by adding it to the list of available IDs: recycledObjectIDs_.
auto initPhysicsFinalize() -> bool virtual
Finalize physics initialization. Setup staticStageObject_ and initialize any other physics-related values for physics-based scenes. Overidden by instancing class if physics is supported.
auto addStageFinalize(const metadata::attributes::StageAttributes::ptr& initAttributes) -> bool virtual
Finalize stage initialization for kinematic stage. Overidden by instancing class if physics is supported.
auto makeAndAddRigidObject(int newObjectID, const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, scene::SceneNode* objectNode) -> bool virtual
Create and initialize a RigidObject, assign it an ID and add it to existingObjects_ map keyed with newObjectID.

Protected variables

assets::ResourceManager& resourceManager_
A reference to a esp::assets::ResourceManager which holds assets that can be accessed by this PhysicsManager.
std::unique_ptr<URDFImporter> urdfImporter_
URDF importer implementation and model cache.
esp::sim::Simulator* simulator_
A pointer to this physics manager's owning simulator.
const std::shared_ptr<const metadata::attributes::PhysicsManagerAttributes> physicsManagerAttributes_
A pointer to the esp::metadata::attributes::PhysicsManagerAttributes describing this physics manager.
PhysicsSimulationLibrary activePhysSimLib_
The current physics library implementation used by this PhysicsManager. Can be used to correctly cast the PhysicsManager to its derived type if necessary.
scene::SceneNode* physicsNode_
The scene::SceneNode which is the parent of all members of the scene graph which exist in the physical world. Used to keep track of all SceneNode's that have physical properties.
physics::RigidStage::ptr staticStageObject_
The scene::SceneNode which represents the static collision geometry of the physical world. Only one staticStageObject_ may exist in a physical world. This RigidStage can only have MotionType::STATIC as it is loaded as static geometry with simulation efficiency in mind. See addStage.
std::shared_ptr<RigidObjectManager> rigidObjectManager_
==== Rigid object memory management ====
std::shared_ptr<ArticulatedObjectManager> articulatedObjectManager_
This manager manages the wrapper objects used to provide safe, direct user access to all existing physics objects.
std::map<int, RigidObject::ptr> existingObjects_
Maps object IDs to all existing physical object instances in the world.
std::map<int, ArticulatedObject::ptr> existingArticulatedObjects_
Maps articulated object IDs to all existing physical object instances in the world.
int nextObjectID_
A counter of unique object ID's allocated thus far. Used to allocate new IDs when recycledObjectIDs_ is empty without needing to check existingObjects_ explicitly.
std::vector<int> recycledObjectIDs_
A list of available object IDs tracked by deallocateObjectID which were previously used by objects since removed from the world with removeObject. These IDs will be re-allocated with allocateObjectID before new IDs are acquired with nextObjectID_.
std::unordered_map<int, RigidConstraintSettings> rigidConstraintSettings_
Tmaps constraint ids to their settings.
std::unordered_map<std::string, int> trajVisIDByName
Maps holding IDs and Names of trajectory visualizations.
std::unordered_map<int, std::string> trajVisNameByID
bool initialized_
Utilities.
double fixedTimeStep_
The fixed amount of time over which to integrate the simulation in discrete steps within stepPhysics. Lower values result in better stability at the cost of worse efficiency and vice versa.
double worldTime_
The current simulation time. Tracks the total amount of time simulated with stepPhysics up to this point.

Enum documentation

enum class esp::physics::PhysicsManager::PhysicsSimulationLibrary

==== physics engines ====

The specific physics implementation used by the current PhysicsManager. Each entry suggests a derived class of PhysicsManager and RigidObject implementing the specific interface to a simulation library.

Enumerators
NoPhysics

The default implemenation of kineamtics through the base PhysicsManager class. Supports MotionType::STATIC and MotionType::KINEMATIC objects of base class RigidObject. If the derived PhysicsManager class for a desired PhysicsSimulationLibrary fails to initialize, it will default to PhysicsSimulationLibrary::NoPhysics.

Bullet

An implemenation of dynamics through the Bullet Physics library. Supports MotionType::STATIC, MotionType::KINEMATIC, and MotionType::DYNAMIC objects of RigidObject derived class BulletRigidObject. Suggests the use of PhysicsManager derived class BulletPhysicsManager

Function documentation

esp::physics::PhysicsManager::PhysicsManager(assets::ResourceManager& _resourceManager, const std::shared_ptr<const metadata::attributes::PhysicsManagerAttributes>& _physicsManagerAttributes) explicit

Construct a ref PhysicsManager with access to specific resource assets.

Parameters
_resourceManager The esp::assets::ResourceManager which tracks the assets this
_physicsManagerAttributes The PhysicsManagerAttributes template used to instantiate this physics manager. PhysicsManager will have access to.

bool esp::physics::PhysicsManager::initPhysics(scene::SceneNode* node)

Initialization: load physical properties and setup the world.

Parameters
node The scene graph node which will act as the parent of all physical scene and object nodes.

bool esp::physics::PhysicsManager::addStageInstance(const metadata::attributes::StageAttributes::ptr& initAttributes, const metadata::attributes::SceneObjectInstanceAttributes::cptr& stageInstanceAttributes)

Initialize static scene collision geometry from loaded mesh data. Only one 'scene' may be initialized per simulated world, but this scene may contain several components (e.g. GLB hierarchy).

Parameters
initAttributes The attributes structure defining physical properties of the scene. Must be a copy of the attributes stored in the Attributes Manager.
stageInstanceAttributes The stage instance attributes that was used to create this stage. Might be empty.
Returns true if successful and false otherwise

int esp::physics::PhysicsManager::addObjectInstance(const esp::metadata::attributes::SceneObjectInstanceAttributes::cptr& objInstAttributes, const std::string& attributesHandle, bool defaultCOMCorrection = false, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance and place a physics object from a esp::metadata::attributes::SceneObjectInstanceAttributes file.

Parameters
objInstAttributes The attributes that describe the desired state to set this object.
attributesHandle The handle of the object attributes used as the key to query esp::metadata::managers::ObjectAttributesManager.
defaultCOMCorrection The default value of whether COM-based translation correction needs to occur.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group. Will create object regardless, however.
attachmentNode If supplied, attach the new physical object to an existing SceneNode.
lightSetup The string name of the desired lighting setup to use.
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

int esp::physics::PhysicsManager::addObject(const std::string& attributesHandle, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance a physical object from an object properties template in the esp::metadata::managers::ObjectAttributesManager. This method will query for a drawable group from simulator.

Parameters
attributesHandle The handle of the object attributes used as the key to query esp::metadata::managers::ObjectAttributesManager.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group. Will create object regardless, however.
attachmentNode If supplied, attach the new physical object to an existing SceneNode.
lightSetup The string name of the desired lighting setup to use.
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

int esp::physics::PhysicsManager::addObject(int attributesID, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance a physical object from an object properties template in the esp::metadata::managers::ObjectAttributesManager by template ID. This method will query for a drawable group from simulator.

Parameters
attributesID The ID of the object's template in esp::metadata::managers::ObjectAttributesManager
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group. Will create object regardless, however.
attachmentNode If supplied, attach the new physical object to an existing SceneNode.
lightSetup The string name of the desired lighting setup to use.
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

void esp::physics::PhysicsManager::removeObject(int objectId, bool deleteObjectNode = true, bool deleteVisualNode = true) virtual

Remove an object instance from the pysical scene by ID, destroying its scene graph node and removing it from PhysicsManager::existingObjects_.

Parameters
objectId The ID (key) of the object instance in PhysicsManager::existingObjects_.
deleteObjectNode If true, deletes the object's scene node. Otherwise detaches the object from simulation.
deleteVisualNode If true, deletes the object's visual node. Otherwise detaches the object from simulation. Is not considered if deleteObjectNode==true.

int esp::physics::PhysicsManager::getNumRigidObjects() const

Get the number of objects mapped in PhysicsManager::existingObjects_.

Returns The size of PhysicsManager::existingObjects_.

std::vector<int> esp::physics::PhysicsManager::getExistingObjectIDs() const

Get a list of existing object IDs (i.e., existing keys in PhysicsManager::existingObjects_.)

Returns List of object ID keys from PhysicsManager::existingObjects_.

int esp::physics::PhysicsManager::addArticulatedObjectInstance(const std::shared_ptr<const esp::metadata::attributes::SceneAOInstanceAttributes>& aObjInstAttributes, const std::string& attributesHandle, DrawableGroup* drawables = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance and place an ArticulatedObject from a esp::metadata::attributes::SceneAOInstanceAttributes file.

Parameters
aObjInstAttributes The attributes that describe the desired initial state to set for this articulated object.
attributesHandle The handle of the ArticulatedObject attributes used as the key to query esp::metadata::managers::AOAttributesManager for the attributes.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group.
lightSetup The string name of the desired lighting setup to use.
Returns The instanced ArticulatedObject 's ID, mapping to the articulated object in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED. These values come from the same pool used by rigid objects.

int esp::physics::PhysicsManager::addArticulatedObject(const std::string& attributesHandle, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance an ArticulatedObject from an esp::metadata::attributes::ArticulatedObjectAttributes retrieved from the esp::metadata::managers::AOAttributesManager by the given attributesHandle .

Parameters
attributesHandle The handle of the ArticulatedObjectAttributes to use to create the desired ArticulatedObject
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group.
forceReload If true, reload the source URDF from file, replacing the cached model.
lightSetup The string name of the desired lighting setup to use.
Returns The instanced ArticulatedObject 's ID, mapping to the articulated object in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED. These values come from the same pool used by rigid objects.

int esp::physics::PhysicsManager::addArticulatedObject(int attributesID, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Instance an ArticulatedObject from an esp::metadata::attributes::ArticulatedObjectAttributes retrieved from the esp::metadata::managers::AOAttributesManager by the given attributesID .

Parameters
attributesID The ID of the ArticulatedObjectAttributes to use to create the desired ArticulatedObject
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group.
forceReload If true, reload the source URDF from file, replacing the cached model.
lightSetup The string name of the desired lighting setup to use.
Returns The instanced ArticulatedObject 's ID, mapping to the articulated object in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED. These values come from the same pool used by rigid objects.

int esp::physics::PhysicsManager::addArticulatedObjectFromURDF(const std::string& filepath, DrawableGroup* drawables = nullptr, bool fixedBase = false, float globalScale = 1.0, float massScale = 1.0, bool forceReload = false, bool maintainLinkOrder = false, bool intertiaFromURDF = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY)

Load, parse, and import a URDF file instantiating an ArticulatedObject in the world.

Parameters
filepath The fully-qualified filename for the URDF file describing the model the articulated object is to be built from.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group.
fixedBase Whether the base of the ArticulatedObject should be fixed.
globalScale A scale multiplier to be applied uniformly in 3 dimensions to the entire ArticulatedObject.
massScale A scale multiplier to be applied to the mass of the all the components of the ArticulatedObject.
forceReload If true, reload the source URDF from file, replacing the cached model.
maintainLinkOrder If true, maintain the order of link definitions from the URDF file as the link indices.
intertiaFromURDF If true, load the link inertia matrices from the URDF file instead of computing automatically from collision shapes.
lightSetup The string name of the desired lighting setup to use.
Returns The instanced ArticulatedObject 's ID, mapping to the articulated object in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED. These values come from the same pool used by rigid objects.

Not implemented in base PhysicsManager.

void esp::physics::PhysicsManager::removeArticulatedObject(int objectId) virtual

Remove an ArticulatedObject from the world by unique id.

Parameters
objectId The Id of the object to remove

std::vector<int> esp::physics::PhysicsManager::getExistingArticulatedObjectIds() const

Get a list of existing object IDs for articulated objects (i.e., existing keys in PhysicsManager::existingArticulatedObjects_.)

Returns List of object ID keys from PhysicsManager::existingArticulatedObjects_.

void esp::physics::PhysicsManager::stepPhysics(double dt = 0.0) virtual

Step the physical world forward in time. Time may only advance in increments of fixedTimeStep_.

Parameters
dt The desired amount of time to advance the physical world.

void esp::physics::PhysicsManager::setTimestep(double dt) virtual

Set the fixedTimeStep_ of the physical world. See stepPhysics.

Parameters
dt The increment of time by which the physical world will advance.

void esp::physics::PhysicsManager::setGravity(const Magnum::Vector3& gravity) virtual

Set the gravity of the physical world if the world is dyanmic and therefore has a notion of force. By default does nothing since the world is kinematic. Exact implementations of gravity will depend on the specific dynamics of the derived physical simulator class.

Parameters
gravity The desired gravity force of the physical world.

double esp::physics::PhysicsManager::getTimestep() const virtual

Get the fixedTimeStep_ of the physical world. See stepPhysics.

Returns The increment of time, fixedTimeStep_, by which the physical world will advance.

double esp::physics::PhysicsManager::getWorldTime() const virtual

Get the current worldTime_ of the physical world. See stepPhysics.

Returns The amount of time, worldTime_, by which the physical world has advanced.

Magnum::Vector3 esp::physics::PhysicsManager::getGravity() const virtual

Get the current gravity in the physical world. By default returns [0,0,0] since their is no notion of force in a kinematic world.

Returns The current gravity vector in the physical world.

double esp::physics::PhysicsManager::getStageFrictionCoefficient() const virtual

Get the current friction coefficient of the scene collision geometry. See staticStageObject_.

Returns The scalar friction coefficient of the scene geometry.

void esp::physics::PhysicsManager::setStageFrictionCoefficient(const double frictionCoefficient) virtual

Set the friction coefficient of the scene collision geometry. See staticStageObject_.

Parameters
frictionCoefficient The scalar friction coefficient of the scene geometry.

double esp::physics::PhysicsManager::getStageRestitutionCoefficient() const virtual

Get the current coefficient of restitution for the scene collision geometry. This determines the ratio of initial to final relative velocity between the scene and collidiing object. See staticStageObject_. By default this will always return 0, since kinametic scenes have no dynamics.

Returns The scalar coefficient of restitution for the scene geometry.

void esp::physics::PhysicsManager::setStageRestitutionCoefficient(const double restitutionCoefficient) virtual

Set the coefficient of restitution for the scene collision geometry. See staticStageObject_. By default does nothing since kinametic scenes have no dynamics.

Parameters
restitutionCoefficient The scalar coefficient of restitution to set.

int esp::physics::PhysicsManager::checkActiveObjects()

Get the number of objects in PhysicsManager::existingObjects_ considered active by the physics simulator currently in use. See RigidObject::isActive.

Returns The number of active RigidObject instances.

void esp::physics::PhysicsManager::setObjectBBDraw(int physObjectID, DrawableGroup* drawables, bool drawBB)

Set bounding box rendering for the object true or false.

Parameters
physObjectID The object ID and key identifying the object in PhysicsManager::existingObjects_.
drawables The drawables group with which to render the bounding box.
drawBB Set rendering of the bounding box to true or false.

const scene::SceneNode& esp::physics::PhysicsManager::getObjectVisualSceneNode(int physObjectID) const

Get the root node of an object's visual SceneNode subtree.

Parameters
physObjectID The object ID and key identifying the object in PhysicsManager::existingObjects_.
Returns The visual root node.

void esp::physics::PhysicsManager::debugDraw(const Magnum::Matrix4& projTrans) const virtual

Render any debugging visualizations provided by the underlying physics simulator implementation. By default does nothing. See BulletPhysicsManager::debugDraw.

Parameters
projTrans The composed projection and transformation matrix for the render camera.

bool esp::physics::PhysicsManager::contactTest(const int physObjectID) virtual

Check whether an object is in contact with any other objects or the scene.

Parameters
physObjectID The object ID and key identifying the object in PhysicsManager::existingObjects_.
Returns Whether or not the object is in contact with any other collision enabled objects.

int esp::physics::PhysicsManager::getNumActiveContactPoints() virtual

Query the number of contact points that were active during the most recent collision detection check.

Returns the number of active contact points.

Not implemented for default PhysicsManager.

std::vector<ContactPointData> esp::physics::PhysicsManager::getContactPoints() const virtual

Query physics simulation implementation for contact point data from the most recent collision detection cache.

Returns a vector with each entry corresponding to a single contact point.

Not implemented for default PhysicsManager implementation.

void esp::physics::PhysicsManager::setStageIsCollidable(bool collidable)

Set the stage to collidable or not.

Parameters
collidable Whether or not the object should be collision active

bool esp::physics::PhysicsManager::getStageIsCollidable()

Get whether or not the stage is collision active.

Returns Whether or not the stage is set to be collision active

const PhysicsSimulationLibrary& esp::physics::PhysicsManager::getPhysicsSimulationLibrary() const

Return the library implementation type for the simulator currently in use. Use to check for a particular implementation.

Returns The implementation type of this simulator.

metadata::attributes::StageAttributes::ptr esp::physics::PhysicsManager::getStageInitAttributes() const

Get a copy of the template used to initialize the stage.

Returns The initialization settings of the stage or nullptr if the stage is not initialized.

std::shared_ptr<metadata::attributes::PhysicsManagerAttributes> esp::physics::PhysicsManager::getInitializationAttributes() const

Get a copy of the template used to initialize this physics manager.

Returns The initialization settings for this physics manager

RaycastResults esp::physics::PhysicsManager::castRay(const esp::geo::Ray& ray, double maxDistance = 100.0) virtual

Cast a ray into the collision world and return a RaycastResults with hit information.

Parameters
ray The ray to cast. Need not be unit length, but returned hit distances will be in units of ray length.
maxDistance The maximum distance along the ray direction to search. In units of ray length.
Returns The raycast results sorted by distance.

Note: not implemented here in default PhysicsManager as there are no collision objects without a simulation implementation.

std::shared_ptr<RigidObjectManager> esp::physics::PhysicsManager::getRigidObjectManager() const

returns the wrapper manager for the currently created rigid objects.

Returns RigidObject wrapper manager.

std::shared_ptr<ArticulatedObjectManager> esp::physics::PhysicsManager::getArticulatedObjectManager()

returns the wrapper manager for the currently created articulated objects.

Returns ArticulatedObject wrapper manager

bool esp::physics::PhysicsManager::isValidRigidObjectId(const int physObjectID) const

Check if physObjectID represents an existing rigid object.

Parameters
physObjectID Object ID to check
Returns Whether rigid object exists with this id or not.

bool esp::physics::PhysicsManager::isValidArticulatedObjectId(const int physObjectID) const

Check if physObjectID represents an existing articulated object.

Parameters
physObjectID Object ID to check
Returns Whether articulated object exists with this id or not.

int esp::physics::PhysicsManager::createRigidConstraint(const RigidConstraintSettings& settings) virtual

Create a rigid constraint between two objects or an object and the world.

Parameters
settings The datastructure defining the constraint parameters.
Returns The id of the newly created constraint or ID_UNDEFINED if failed.

Note: Method not implemented for base PhysicsManager.

void esp::physics::PhysicsManager::updateRigidConstraint(int constraintId, const RigidConstraintSettings& settings) virtual

Update the settings of a rigid constraint.

Parameters
constraintId The id of the constraint to update.
settings The new settings of the constraint.

Note: Method not implemented for base PhysicsManager.

void esp::physics::PhysicsManager::removeRigidConstraint(int constraintId) virtual

Remove a rigid constraint by id.

Parameters
constraintId The id of the constraint to remove.

Note: Method not implemented for base PhysicsManager.

RigidConstraintSettings esp::physics::PhysicsManager::getRigidConstraintSettings(int constraintId) const

Get a copy of the settings for an existing rigid constraint.

Parameters
constraintId The id of the constraint.
Returns The settings of the constraint.

void esp::physics::PhysicsManager::buildCurrentStateSceneAttributes(const metadata::attributes::SceneInstanceAttributes::ptr& sceneInstanceAttrs) const

This will populate the passed sceneInstanceAttrs with the current stage, object and articulated object instances reflecting the current state of the physics world.

Parameters
sceneInstanceAttrs A copy of the intialization attributes that created the current scene. The various object instance attributes will be overwritten by the current scene state data.

int esp::physics::PhysicsManager::addTrajectoryObject(const std::string& trajVisName, const std::vector<Mn::Vector3>& pts, const std::vector<Mn::Color3>& colorVec, int numSegments = 3, float radius = .001, bool smooth = false, int numInterp = 10, DrawableGroup* drawables = nullptr)

Compute a trajectory visualization for the passed points.

Parameters
trajVisName The name to use for the trajectory visualization
pts The points of a trajectory, in order
colorVec Array of colors for trajectory tube.
numSegments The number of the segments around the circumference of the tube. Must be greater than or equal to 3.
radius The radius of the tube.
smooth Whether to smooth the points in the trajectory or not. Will build a much bigger mesh
numInterp The number of interpolations between each trajectory point, if smoothed
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object. If nullptr, will attempt to query Simulator to retrieve a group.
Returns The ID of the object created for the visualization

bool esp::physics::PhysicsManager::removeTrajVisByName(const std::string& trajVisName)

Remove a trajectory visualization by name.

Parameters
trajVisName The name of the trajectory visualization to remove.
Returns whether successful or not.

bool esp::physics::PhysicsManager::removeTrajVisByID(int trajVisObjID)

Remove a trajectory visualization by object ID.

Parameters
trajVisObjID The object ID of the trajectory visualization to remove.
Returns whether successful or not.

int esp::physics::PhysicsManager::addObjectAndSaveAttributes(const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, DrawableGroup* drawables = nullptr, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY, bool defaultCOMCorrection = false, esp::metadata::attributes::SceneObjectInstanceAttributes::cptr objInstAttributes = nullptr) protected

This method will create a physical object using the passed values by calling addObjectInternal, will initialize its state and save it's instantiation attributes.

Parameters
objectAttributes The object's template to use to instantiate the object.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object.
attachmentNode If supplied, attach the new physical object to an existing SceneNode.
lightSetup The string name of the desired lighting setup to use.
defaultCOMCorrection The default value of whether COM-based translation correction needs to occur. Only non-default from addObjectInstance method.
objInstAttributes The attributes that describe the desired state to set this object on creation. If nullptr, create an empty default instance and populate it properly based on the object config.
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

int esp::physics::PhysicsManager::addObjectInternal(const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, DrawableGroup* drawables, scene::SceneNode* attachmentNode = nullptr, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) protected

Instance a physical object from an ObjectAttributes template.

Parameters
objectAttributes The object's template to use to instantiate the object.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized object.
attachmentNode If supplied, attach the new physical object to an existing SceneNode.
lightSetup The string name of the desired lighting setup to use.
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

int esp::physics::PhysicsManager::addArticulatedObjectAndSaveAttributes(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes, DrawableGroup* drawables = nullptr, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY, esp::metadata::attributes::SceneAOInstanceAttributes::cptr artObjInstAttributes = nullptr) protected

This method will create a physical object using the passed values by calling addArticulatedObjectInternal, will initialize its state and save it's instantiation attributes.

Parameters
artObjAttributes The ArticulatedObject's template to use to create it.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized ArticulatedObject.
forceReload If true, force the reload of the source URDF from file, replacing the cached model if it exists.
lightSetup The string name of the desired lighting setup to use.
artObjInstAttributes
Returns the instanced object's ID, mapping to it in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED.

int esp::physics::PhysicsManager::addArticulatedObjectInternal(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes, DrawableGroup* drawables, bool forceReload = false, const std::string& lightSetup = DEFAULT_LIGHTING_KEY) virtual protected

Load, parse, and import a URDF file instantiating an ArticulatedObject in the world based on the urdf filepath specified in esp::metadata::attributes::ArticulatedObjectAttributes. This version requires drawables to be provided.

Parameters
artObjAttributes The ArticulatedObject's template to use to create it.
drawables Reference to the scene graph drawables group to enable rendering of the newly initialized ArticulatedObject.
forceReload If true, force the reload of the source URDF from file, replacing the cached model if it exists.
lightSetup The string name of the desired lighting setup to use.
Returns The instanced ArticulatedObject 's ID, mapping to the articulated object in PhysicsManager::existingObjects_ if successful, or esp::ID_UNDEFINED. These values come from the same pool used by rigid objects.

Not implemented in base PhysicsManager.

bool esp::physics::PhysicsManager::removeTrajVisObjectAndAssets(int trajVisObjID, const std::string& trajVisName) protected

Internal use only. Remove a trajectory object, its mesh, and all references to it.

Parameters
trajVisObjID The object ID of the trajectory visualization to remove.
trajVisName The name of the trajectory visualization to remove.
Returns whether successful or not.

std::map<int, RigidObject::ptr>::iterator esp::physics::PhysicsManager::getRigidObjIteratorOrAssert(const int physObjectID) protected

Retrieve an iterator to a given object ID's value if it is valid (i.e. it refers to an existing rigid object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.

Parameters
physObjectID The object ID to validate.
Returns iterator to map entry or to end of map if DNE

std::map<int, ArticulatedObject::ptr>::iterator esp::physics::PhysicsManager::getArticulatedObjIteratorOrAssert(const int physObjectID) protected

Retrieve an iterator to a given articulated object ID's value if it is valid (i.e. it refers to an existing articulated object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.

Parameters
physObjectID The articulated object ID to validate.
Returns iterator to map entry or to end of map if DNE

std::map<int, RigidObject::ptr>::const_iterator esp::physics::PhysicsManager::getConstRigidObjIteratorOrAssert(const int physObjectID) const protected

Retrieve an iterator to a given object ID's value if it is valid (i.e. it refers to an existing rigid object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.

Parameters
physObjectID The object ID to validate.
Returns iterator to map entry or to end of map if DNE

std::map<int, ArticulatedObject::ptr>::const_iterator esp::physics::PhysicsManager::getConstArticulatedObjIteratorOrAssert(const int physObjectID) const protected

Retrieve an iterator to a given articulated object ID's value if it is valid (i.e. it refers to an existing articulated object). Terminate the program and report an error if not. This function is intended to unify object ID checking for PhysicsManager functions.

Parameters
physObjectID The articulated object ID to validate.
Returns iterator to map entry or to end of map if DNE

int esp::physics::PhysicsManager::allocateObjectID() protected

Acquire a new ObjectID by recycling the ID of an object removed with removeObject or by incrementing nextObjectID_. See addObject.

Returns The newly allocated ObjectID.

int esp::physics::PhysicsManager::deallocateObjectID(int physObjectID) protected

Recycle the ID of an object removed with removeObject by adding it to the list of available IDs: recycledObjectIDs_.

Parameters
physObjectID The ID to recycle.
Returns The recycled object ID.

bool esp::physics::PhysicsManager::addStageFinalize(const metadata::attributes::StageAttributes::ptr& initAttributes) virtual protected

Finalize stage initialization for kinematic stage. Overidden by instancing class if physics is supported.

Parameters
initAttributes the attributes structure defining physical properties of the stage.
Returns true if successful and false otherwise

bool esp::physics::PhysicsManager::makeAndAddRigidObject(int newObjectID, const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes, scene::SceneNode* objectNode) virtual protected

Create and initialize a RigidObject, assign it an ID and add it to existingObjects_ map keyed with newObjectID.

Parameters
newObjectID valid object ID for the new object
objectAttributes The physical object's template
objectNode Valid, existing scene node
Returns whether the object has been successfully initialized and added to existingObjects_ map

Variable documentation

std::shared_ptr<RigidObjectManager> esp::physics::PhysicsManager::rigidObjectManager_ protected

==== Rigid object memory management ====

This manager manages the wrapper objects used to provide safe, direct user access to all existing physics objects.

bool esp::physics::PhysicsManager::initialized_ protected

Utilities.

Tracks whether or not this PhysicsManager has already been initialized with initPhysics.