class
BulletPhysicsManagerDynamic stage and object manager interfacing with Bullet physics engine: https:/
Enables RigidObject simulation with MotionType::
This class handles initialization and stepping of the world as well as getting and setting global simulation parameters. The BulletRigidObject class handles most of the specific implementations for object interactions with Bullet.
Base classes
- class PhysicsManager
- 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.
Constructors, destructors, conversion operators
-
BulletPhysicsManager(assets::
ResourceManager& _resourceManager, const std:: shared_ptr<const metadata:: attributes:: PhysicsManagerAttributes>& _physicsManagerAttributes) explicit - Construct a BulletPhysicsManager with access to specific resources assets.
- ~BulletPhysicsManager() override
- Destructor which destructs necessary Bullet physics structures.
Public functions
-
auto attachLinkGeometry(ArticulatedLink* linkObject,
const std::
shared_ptr<metadata:: URDF:: Link>& link, gfx:: DrawableGroup* drawables, const std:: string& lightSetup, int semanticId) -> bool - Use the metadata stored in metadata::URDF::Link to instance all visual shapes for a link into the SceneGraph.
- void removeObject(int objectId, bool deleteObjectNode = true, bool deleteVisualNode = true) override
- Override of PhysicsManager::
removeObject to also remove any active Bullet physics constraints for the object. - void removeArticulatedObject(int objectId) override
- Override of PhysicsManager::
removeArticulatedObject to also remove any active Bullet physics constraints for the object. - void stepPhysics(double dt) override
- Step the physical world forward in time. Time may only advance in increments of fixedTimeStep_
. See btMultiBodyDynamicsWorld:: stepSimulation. -
void setGravity(const Magnum::
Vector3& gravity) override - Set the gravity of the physical world.
-
auto getGravity() const -> Magnum::
Vector3 override - Get the current gravity in the physical world.
- void setStageFrictionCoefficient(double frictionCoefficient) override
- Set the friction coefficient of the stage collision geometry. See staticStageObject_
. See BulletRigidObject:: setFrictionCoefficient. - void setStageRestitutionCoefficient(double restitutionCoefficient) override
- Set the coefficient of restitution for the stage collision geometry. See staticStageObject_
. See BulletRigidObject:: setRestitutionCoefficient. - auto getStageFrictionCoefficient() const -> double override
- Get the current friction coefficient of the stage collision geometry. See staticStageObject_
and BulletRigidObject:: getFrictionCoefficient. - auto getStageRestitutionCoefficient() const -> double override
- Get the current coefficient of restitution for the stage collision geometry. This determines the ratio of initial to final relative velocity between the stage and colliding object. See staticStageObject_
and BulletRigidObject::getRestitutionCoefficient. -
auto getCollisionShapeAabb(int physObjectID) const -> Magnum::
Range3D - Query the Aabb from bullet physics for the root compound shape of a rigid body in its local space. See btCompoundShape::
getAabb. -
auto getStageCollisionShapeAabb() const -> Magnum::
Range3D - Query the Aabb from bullet physics for the root compound shape of the static stage in its local space. See btCompoundShape::
getAabb. -
void debugDraw(const Magnum::
Matrix4& projTrans) const override - Render the debugging visualizations provided by Magnum::
BulletIntegration:: DebugDraw. This draws wireframes for all collision objects. -
auto getContactPoints() const -> std::
vector<ContactPointData> override - Return ContactPointData objects describing the contacts from the most recent physics substep.
-
auto castRay(const esp::
geo:: Ray& ray, double maxDistance = 100.0, double bufferDistance = 0.08) -> RaycastResults override - Cast a ray into the collision world and return a RaycastResults with hit information.
- auto getNumActiveContactPoints() -> int override
- Query the number of contact points that were active during the collision detection check.
- auto getNumActiveOverlappingPairs() -> int override
- Query the number of overlapping pairs that were active during the collision detection check.
-
auto getStepCollisionSummary() -> std::
string override - Get a summary of collision-processing from the last physics step.
- void performDiscreteCollisionDetection() override
- Perform discrete collision detection for the scene.
- auto createRigidConstraint(const RigidConstraintSettings& settings) -> int override
- Create a rigid constraint between two objects or an object and the world.
- void updateRigidConstraint(int constraintId, const RigidConstraintSettings& settings) override
- Update the settings of a rigid constraint.
- void removeRigidConstraint(int constraintId) override
- Remove a rigid constraint by id.
- auto shared_from_this() -> BulletPhysicsManager::ptr
- utilize PhysicsManager's enable shared
Protected functions
-
auto addArticulatedObjectInternal(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes,
DrawableGroup* drawables,
bool forceReload = false,
const std::
string& lightSetup = DEFAULT_ LIGHTING_ KEY) -> int override - 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 initPhysicsFinalize() -> bool override
- Finalize physics initialization: Setup staticStageObject_ and initialize any other physics-related values.
- auto getRigidObjectWrapper() -> esp::physics::ManagedRigidObject::ptr override
- Create an object wrapper appropriate for this physics manager. Overridden if called by dynamics-library-enabled PhysicsManager.
- auto getArticulatedObjectWrapper() -> esp::physics::ManagedArticulatedObject::ptr override
- Create an articulated object wrapper appropriate for this physics manager. Overridden if called by dynamics-library-enabled PhysicsManager.
- auto addStageFinalize(const metadata::attributes::StageAttributes::ptr& initAttributes) -> bool override
- Finalize stage initialization. Checks that the collision mesh can be used by Bullet. See BulletRigidObject::initializeStage. Bullet mesh conversion adapted from: https:/
/ github.com/ mosra/ magnum-integration/ issues/ 20. -
auto makeAndAddRigidObject(int newObjectID,
const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes,
scene::
SceneNode* objectNode) -> bool override - Create and initialize an RigidObject and add it to existingObjects_ map keyed with newObjectID.
Protected variables
- int nextConstraintId_
- counter for constraint id generation
-
std::
unordered_map<int, std:: unique_ptr<btMultiBodyPoint2Point>> articulatedP2PConstraints_ - caches for various types of Bullet rigid constraint objects.
-
std::
unordered_map<int, std:: unique_ptr<btMultiBodyFixedConstraint>> articulatedFixedConstraints_ -
std::
unordered_map<int, std:: unique_ptr<btPoint2PointConstraint>> rigidP2PConstraints_ -
std::
unordered_map<int, std:: unique_ptr<btFixedConstraint>> rigidFixedConstraints_ -
std::
unique_ptr<btRigidBody> globalFrameObject -
std::
unordered_map<int, std:: vector<int>> objectConstraints_ - btDbvtBroadphase bBroadphase_
- btDefaultCollisionConfiguration bCollisionConfig_
- btMultiBodyConstraintSolver bSolver_
- btCollisionDispatcher bDispatcher_
-
std::
shared_ptr<btMultiBodyDynamicsWorld> bWorld_ - A pointer to the Bullet world. See btMultiBodyDynamicsWorld.
-
std::
unique_ptr<Magnum:: BulletIntegration:: DebugDraw> debugDrawer_ -
std::
shared_ptr<std:: map<const btCollisionObject*, int>> collisionObjToObjIds_ - double recentTimeStep_
- necessary to acquire forces from impulses
- int recentNumSubStepsTaken_
- for recent call to stepPhysics
Function documentation
esp:: physics:: BulletPhysicsManager:: BulletPhysicsManager(assets:: ResourceManager& _resourceManager,
const std:: shared_ptr<const metadata:: attributes:: PhysicsManagerAttributes>& _physicsManagerAttributes) explicit
Construct a BulletPhysicsManager with access to specific resources assets.
Parameters | |
---|---|
_resourceManager | The esp:: |
_physicsManagerAttributes |
bool esp:: physics:: BulletPhysicsManager:: attachLinkGeometry(ArticulatedLink* linkObject,
const std:: shared_ptr<metadata:: URDF:: Link>& link,
gfx:: DrawableGroup* drawables,
const std:: string& lightSetup,
int semanticId)
Use the metadata stored in metadata::URDF::Link to instance all visual shapes for a link into the SceneGraph.
Parameters | |
---|---|
linkObject | The Habitat-side ArticulatedLink to which visual shapes will be attached. |
link | The metadata::URDF::Model's link with visual shape and transform metadata. |
drawables | The SceneGraph's DrawableGroup with which the visual shapes will be rendered. |
lightSetup | The string name of the desired lighting setup to use. |
semanticId | |
Returns | Whether or not the render shape instancing was successful. |
void esp:: physics:: BulletPhysicsManager:: stepPhysics(double dt) override
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:: BulletPhysicsManager:: setGravity(const Magnum:: Vector3& gravity) override
Set the gravity of the physical world.
Parameters | |
---|---|
gravity | The desired gravity force of the physical world. |
Magnum:: Vector3 esp:: physics:: BulletPhysicsManager:: getGravity() const override
Get the current gravity in the physical world.
Returns | The current gravity vector in the physical world. |
---|
void esp:: physics:: BulletPhysicsManager:: setStageFrictionCoefficient(double frictionCoefficient) override
Set the friction coefficient of the stage collision geometry. See staticStageObject_
Parameters | |
---|---|
frictionCoefficient | The scalar friction coefficient of the stage geometry. |
void esp:: physics:: BulletPhysicsManager:: setStageRestitutionCoefficient(double restitutionCoefficient) override
Set the coefficient of restitution for the stage collision geometry. See staticStageObject_
Parameters | |
---|---|
restitutionCoefficient | The scalar coefficient of restitution to set. |
double esp:: physics:: BulletPhysicsManager:: getStageFrictionCoefficient() const override
Get the current friction coefficient of the stage collision geometry. See staticStageObject_
Returns | The scalar friction coefficient of the stage geometry. |
---|
double esp:: physics:: BulletPhysicsManager:: getStageRestitutionCoefficient() const override
Get the current coefficient of restitution for the stage collision geometry. This determines the ratio of initial to final relative velocity between the stage and colliding object. See staticStageObject_
Returns | The scalar coefficient of restitution for the stage geometry. |
---|
Magnum:: Range3D esp:: physics:: BulletPhysicsManager:: getCollisionShapeAabb(int physObjectID) const
Query the Aabb from bullet physics for the root compound shape of a rigid body in its local space. See btCompoundShape::
Parameters | |
---|---|
physObjectID | The object ID and key identifying the object in PhysicsManager:: |
Returns | The Aabb. |
Magnum:: Range3D esp:: physics:: BulletPhysicsManager:: getStageCollisionShapeAabb() const
Query the Aabb from bullet physics for the root compound shape of the static stage in its local space. See btCompoundShape::
Returns | The stage collision Aabb. |
---|
void esp:: physics:: BulletPhysicsManager:: debugDraw(const Magnum:: Matrix4& projTrans) const override
Render the debugging visualizations provided by Magnum::
Parameters | |
---|---|
projTrans | The composed projection and transformation matrix for the render camera. |
std:: vector<ContactPointData> esp:: physics:: BulletPhysicsManager:: getContactPoints() const override
Return ContactPointData objects describing the contacts from the most recent physics substep.
Returns | a vector with each entry corresponding to a single contact point. |
---|
This implementation is roughly identical to PyBullet's getContactPoints.
RaycastResults esp:: physics:: BulletPhysicsManager:: castRay(const esp:: geo:: Ray& ray,
double maxDistance = 100.0,
double bufferDistance = 0.08) override
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. |
bufferDistance | The casts the ray from this distance behind the origin in the inverted ray direction to avoid errors related to casting rays inside a collision shape's margin. |
Returns | The raycast results sorted by distance. |
int esp:: physics:: BulletPhysicsManager:: getNumActiveContactPoints() override
Query the number of contact points that were active during the collision detection check.
Returns | the number of active contact points. |
---|
An object resting on another object will involve several active contact points. Once both objects are asleep, the contact points are inactive. This count can be used as a metric for the complexity/cost of collision-handling in the current scene.
int esp:: physics:: BulletPhysicsManager:: getNumActiveOverlappingPairs() override
Query the number of overlapping pairs that were active during the collision detection check.
Returns | the number of active overlapping pairs. |
---|
When object bounding boxes overlap and either object is active, additional "narrowphase" collision-detection must be run. This count is a proxy for complexity/cost of collision-handling in the current scene. See also getNumActiveContactPoints.
int esp:: physics:: BulletPhysicsManager:: createRigidConstraint(const RigidConstraintSettings& settings) override
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. |
void esp:: physics:: BulletPhysicsManager:: updateRigidConstraint(int constraintId,
const RigidConstraintSettings& settings) override
Update the settings of a rigid constraint.
Parameters | |
---|---|
constraintId | The id of the constraint to update. |
settings | The new settings of the constraint. |
void esp:: physics:: BulletPhysicsManager:: removeRigidConstraint(int constraintId) override
Remove a rigid constraint by id.
Parameters | |
---|---|
constraintId | The id of the constraint to remove. |
int esp:: physics:: BulletPhysicsManager:: addArticulatedObjectInternal(const esp::metadata::attributes::ArticulatedObjectAttributes::ptr& artObjAttributes,
DrawableGroup* drawables,
bool forceReload = false,
const std:: string& lightSetup = DEFAULT_ LIGHTING_ KEY) override protected
Load, parse, and import a URDF file instantiating an ArticulatedObject in the world based on the urdf filepath specified in esp::
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:: |
bool esp:: physics:: BulletPhysicsManager:: addStageFinalize(const metadata::attributes::StageAttributes::ptr& initAttributes) override protected
Finalize stage initialization. Checks that the collision mesh can be used by Bullet. See BulletRigidObject::initializeStage. Bullet mesh conversion adapted from: https:/
Parameters | |
---|---|
initAttributes | The attributes structure defining physical properties of the stage. |
Returns | true if successful and false otherwise |
bool esp:: physics:: BulletPhysicsManager:: makeAndAddRigidObject(int newObjectID,
const esp::metadata::attributes::ObjectAttributes::ptr& objectAttributes,
scene:: SceneNode* objectNode) override protected
Create and initialize an RigidObject and add it to existingObjects_ map keyed with newObjectID.
Parameters | |
---|---|
newObjectID | valid object ID for the new object |
objectAttributes | The object's template |
objectNode | Valid, existing scene node |
Returns | whether the object has been successfully initialized and added to existingObjects_ map |
Variable documentation
std:: unique_ptr<btRigidBody> esp:: physics:: BulletPhysicsManager:: globalFrameObject protected
when constraining objects to the global frame, a dummy object with 0 mass is required.
std:: unordered_map<int, std:: vector<int>> esp:: physics:: BulletPhysicsManager:: objectConstraints_ protected
Maps object ids to a list of active constraints referencing the object for use in constraint clean-up and object sleep state management.
std:: shared_ptr<std:: map<const btCollisionObject*, int>> esp:: physics:: BulletPhysicsManager:: collisionObjToObjIds_ protected
keep a map of collision objects to object ids for quick lookups from Bullet collision checking.