class
#include <esp/physics/PhysicsObjectBase.h>
PhysicsObjectBase
Derived classes
- class ArticulatedObject
- An articulated rigid object (i.e. kinematic chain). Abstract class to be derived by physics simulator specific implementations.
- class RigidBase
- This class specifies the functionality expected of rigid objects and stages, particularly with regard to dynamic simulation, if such a library, such as bullet, is available.
Constructors, destructors, conversion operators
-
PhysicsObjectBase(scene::
SceneNode* bodyNode, int objectId, const assets:: ResourceManager& resMgr) - ~PhysicsObjectBase() defaulted override
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& -
template<class T>auto getInitializationAttributes() const -> std::
shared_ptr<T> - Get a copy of the template used to initialize this object or scene.
- auto getMotionType() const -> MotionType
- Get the MotionType of the object. See setMotionType.
- void setMotionType(MotionType mt) pure virtual
- Set the MotionType of the object. If the construct is a physics::
RigidStage, it can only be physics:: MotionType:: STATIC. If the object is physics:: RigidObject it can also be set to physics:: MotionType:: KINEMATIC. Only if a dervied physics:: PhysicsManager implementing dynamics is in use can the object be set to physics:: MotionType:: DYNAMIC. - auto getObjectID() const -> int
- Get object's ID.
-
auto getObjectName() const -> std::
string - Object name, to facilitate access.
-
void setObjectName(const std::
string& name) -
auto getSceneNode() const -> const scene::
SceneNode& - Get a const reference to this physica object's root SceneNode for info query purposes.
- auto isActive() const -> 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(bool active) virtual
- Set an object as being actively simulated or sleeping. Kinematic objects are always active, but derived dynamics implementations may not be.
- auto contactTest() -> bool virtual
- Return result of a discrete contact test between the object and collision world.
- void overrideCollisionGroup(CollisionGroup group) virtual
- Manually set the collision group for an object.
-
void setLightSetup(const std::
string& lightSetupKey) - Set the light setup of this rigid.
-
void setTransformation(const Magnum::
Matrix4& transformation) virtual - Set the 4x4 transformation matrix of the object kinematically. Calling this during simulation of a physics::
MotionType:: DYNAMIC object is not recommended. -
auto getTransformation() const -> Magnum::
Matrix4 virtual - Get the 4x4 transformation matrix of the object.
-
void setTranslation(const Magnum::
Vector3& vector) virtual - Set the 3D position of the object kinematically. Calling this during simulation of a physics::
MotionType:: DYNAMIC object is not recommended. -
auto transformLocalPointsToWorld(const std::
vector<Mn:: Vector3>& points, int linkID = ID_ UNDEFINED) const -> std:: vector<Mn:: Vector3> virtual - Given the list of passed points in this object's local space, return those points transformed to world space.
-
auto transformWorldPointsToLocal(const std::
vector<Mn:: Vector3>& points, int linkID = ID_ UNDEFINED) const -> std:: vector<Mn:: Vector3> virtual - Given the list of passed points in world space, return those points transformed to this object's local space.
-
auto getTranslation() const -> Magnum::
Vector3 virtual - Get the 3D position of the object.
-
void setRotation(const Magnum::
Quaternion& quaternion) virtual - Set the orientation of the object kinematically. Calling this during simulation of a physics::
MotionType:: DYNAMIC object is not recommended. -
auto getRotation() const -> Magnum::
Quaternion virtual - Get the orientation of the object.
-
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 physics::
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 physics::
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 physics::
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 physics::
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 physics::
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 physics::
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 physics::
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 physics::
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 physics::
MotionType:: DYNAMIC object is not recommended. - void deferUpdate() virtual
- Activate deferred updates, preventing SceneNode state changes until updateNodes is called to prevent SceneGraph pollution during render.
- void updateNodes(bool force = false) virtual
- Disable deferred updates if active and sets SceneNode states from internal object physics states.
- void resetStateFromSceneInstanceAttr() pure virtual
- Set or reset the object's state using the object's specified
sceneInstanceAttributes_
. -
template<class U>void setSceneInstanceAttr(std::
shared_ptr<U> instanceAttr) - Set this object's metadata::
attributes:: SceneObjectInstanceAttributes used to place the object within the scene. -
auto getVisualSceneNodes() const -> std::
vector<scene:: SceneNode*> pure virtual - Get pointers to this physics object's visual scene nodes.
- auto getUserAttributes() const -> core::config::Configuration::ptr
- void setUserAttributes(core::config::Configuration::ptr attr)
- This function will overwrite this object's existing user-defined attributes with
attr
. - void mergeUserAttributes(const core::config::Configuration::ptr& attr)
- This function will merge this object's existing user-defined attributes with
attr
by overwriting it withattr
. - auto getMarkerSets() const -> metadata::attributes::MarkerSets::ptr
- Get a reference to the existing MarkerSets for this object.
- void setMarkerSets(metadata::attributes::MarkerSets::ptr attr)
- This function will overwrite this object's existing MarkerSets attributes with
attr
. - void mergeMarkerSets(const metadata::attributes::MarkerSets::ptr& attr)
- This function will merge this object's existing MarkerSets attributes with
attr
by overwriting it withattr
. -
auto getMarkerPointsLocal() const -> std::
unordered_map<std:: string, std:: unordered_map<std:: string, std:: unordered_map<std:: string, std:: vector<Mn:: Vector3>>>> - Retrieves the hierarchical map-of-map-of-maps containing the MarkerSets constituent marker points, in local space (which is the space they are given in).
-
auto getMarkerPointsGlobal() const -> std::
unordered_map<std:: string, std:: unordered_map<std:: string, std:: unordered_map<std:: string, std:: vector<Mn:: Vector3>>>> virtual - Retrieves the hierarchical map-of-map-of-maps containing the MarkerSets constituent marker points, in local space (which is the space they are given in).
-
auto getScale() const -> Magnum::
Vector3 virtual - Get the scale of the object set during initialization.
- auto isArticulated() const -> bool
- Return whether or not this object is articulated. Override in ArticulatedObject.
-
auto getAabb() -> const Mn::
Range3D& virtual - Return the local axis-aligned bounding box of the this object.
-
template<class T>void setManagedObjectPtr(std::
shared_ptr<T> managedObjPtr) - Set the managed object used to reference this object externally (i.e. via python)
Protected functions
-
template<class T>auto getManagedObjectPtrInternal() const -> std::
shared_ptr<T> - Accessed Internally. Get the Managed Object that references this object.
- void setIsArticulated(bool isArticulated)
- Used Internally on object creation. Set whether or not this object is articulated.
-
template<class T>auto getInitObjectInstanceAttrCopyInternal() const -> std::
shared_ptr<T> - Accessed internally. Get an appropriately cast copy of the metadata::
attributes:: SceneObjectInstanceAttributes used to place the object within the scene. -
template<class T>auto getInitObjectInstanceAttrInternal() const -> std::
shared_ptr<const T> - Accessed internally. Get the metadata::
attributes:: SceneObjectInstanceAttributes used to create and place the object within the scene, appropriately cast for object type. -
auto getUncorrectedTranslation() const -> Magnum::
Vector3 virtual - Reverses the COM correction transformation for objects that require it. Currently a simple passthrough for stages and articulated objects.
-
template<class T>auto getCurrentObjectInstanceAttrInternal() -> std::
shared_ptr<T> - Accessed internally. Get an appropriately cast copy of the metadata::
attributes:: SceneObjectInstanceAttributes used to place the object within the scene, updated to have the current transformation and status of the object. - void syncPose() virtual
- Used to synchronize other simulator's notion of the object state after it was changed kinematically. Must be called automatically on kinematic updates.
-
void setScale(const Magnum::
Vector3& creationScale) - Set the object's creation scale.
Protected variables
- bool isDeferringUpdate_
- if true visual nodes are not updated from physics simulation such that the SceneGraph is not polluted during render
-
std::
string objectName_ - An assignable name for this object.
- MotionType objectMotionType_
- The MotionType of the object. Determines what operations can be performed on this object.
- int objectId_
- Access for the object to its own PhysicsManager id.
-
const assets::
ResourceManager& resMgr_ - Reference to the ResourceManager for internal access to the object's asset data.
- core::config::Configuration::ptr userAttributes_
- Stores user-defined attributes for this object, held as a smart pointer to a esp::
core:: config:: Configuration. These attributes are not internally processed by habitat, but provide a "scratch pad" for the user to access and save important information and metadata. - metadata::attributes::MarkerSets::ptr markerSets_
- Stores a reference to the markersets for this object, held as a smart pointer to a MarkerSets construct, which is an alias for a esp::
core:: config:: Configuration. - metadata::attributes::AbstractAttributes::cptr objInitAttributes_
- Saved template attributes when the object was initialized.
Function documentation
template<class T>
std:: shared_ptr<T> esp:: physics:: PhysicsObjectBase:: 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 or nullptr if no template exists. |
---|
MotionType esp:: physics:: PhysicsObjectBase:: getMotionType() const
Get the MotionType of the object. See setMotionType.
Returns | The object's current MotionType. |
---|
void esp:: physics:: PhysicsObjectBase:: setMotionType(MotionType mt) pure virtual
Set the MotionType of the object. If the construct is a physics::
Parameters | |
---|---|
mt | The desired MotionType. |
const scene:: SceneNode& esp:: physics:: PhysicsObjectBase:: getSceneNode() const
Get a const reference to this physica object's root SceneNode for info query purposes.
Returns | Const reference to the object's scene node. |
---|
bool esp:: physics:: PhysicsObjectBase:: isActive() const 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. |
---|
void esp:: physics:: PhysicsObjectBase:: setActive(bool active) virtual
Set an object as being actively simulated or sleeping. Kinematic objects are always active, but derived dynamics implementations may not be.
Parameters | |
---|---|
active | Whether to activate or sleep the object |
bool esp:: physics:: PhysicsObjectBase:: contactTest() virtual
Return result of a discrete contact test between the object and collision world.
Returns | Whether or not the object is in contact with any other collision enabled objects. |
---|
void esp:: physics:: PhysicsObjectBase:: overrideCollisionGroup(CollisionGroup group) virtual
Manually set the collision group for an object.
Parameters | |
---|---|
group | The desired CollisionGroup for the object. |
void esp:: physics:: PhysicsObjectBase:: setLightSetup(const std:: string& lightSetupKey)
Set the light setup of this rigid.
Parameters | |
---|---|
lightSetupKey | gfx:: |
void esp:: physics:: PhysicsObjectBase:: setTransformation(const Magnum:: Matrix4& transformation) virtual
Set the 4x4 transformation matrix of the object kinematically. Calling this during simulation of a physics::
Parameters | |
---|---|
transformation | The desired 4x4 transform of the object. |
void esp:: physics:: PhysicsObjectBase:: setTranslation(const Magnum:: Vector3& vector) virtual
Set the 3D position of the object kinematically. Calling this during simulation of a physics::
Parameters | |
---|---|
vector | The desired 3D position of the object. |
std:: vector<Mn:: Vector3> esp:: physics:: PhysicsObjectBase:: transformLocalPointsToWorld(const std:: vector<Mn:: Vector3>& points,
int linkID = ID_ UNDEFINED) const virtual
Given the list of passed points in this object's local space, return those points transformed to world space.
Parameters | |
---|---|
points | vector of points in object local space |
linkID | Unused for rigids. |
Returns | vector of points transformed into world space |
std:: vector<Mn:: Vector3> esp:: physics:: PhysicsObjectBase:: transformWorldPointsToLocal(const std:: vector<Mn:: Vector3>& points,
int linkID = ID_ UNDEFINED) const virtual
Given the list of passed points in world space, return those points transformed to this object's local space.
Parameters | |
---|---|
points | vector of points in world space |
linkID | Unused for rigids. |
Returns | vector of points transformed to be in local space |
void esp:: physics:: PhysicsObjectBase:: setRotation(const Magnum:: Quaternion& quaternion) virtual
Set the orientation of the object kinematically. Calling this during simulation of a physics::
Parameters | |
---|---|
quaternion | The desired orientation of the object. |
void esp:: physics:: PhysicsObjectBase:: translate(const Magnum:: Vector3& vector) virtual
Modify the 3D position of the object kinematically by translation. Calling this during simulation of a physics::
Parameters | |
---|---|
vector | The desired 3D vector by which to translate the object. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
vector | The desired 3D vector in the object's ocal coordinate system by which to translate the object. |
void esp:: physics:: PhysicsObjectBase:: 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::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
normalizedAxis | The desired unit vector axis of rotation. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
normalizedAxis | The desired unit vector axis of rotation in the local coordinate system. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: 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 physics::
Parameters | |
---|---|
angleInRad | The angle of rotation in radians. |
void esp:: physics:: PhysicsObjectBase:: updateNodes(bool force = false) virtual
Disable deferred updates if active and sets SceneNode states from internal object physics states.
Parameters | |
---|---|
force | If set, update sleeping nodes as well as active nodes. |
template<class U>
void esp:: physics:: PhysicsObjectBase:: setSceneInstanceAttr(std:: shared_ptr<U> instanceAttr)
Set this object's metadata::
Parameters | |
---|---|
instanceAttr | The metadata:: |
std:: vector<scene:: SceneNode*> esp:: physics:: PhysicsObjectBase:: getVisualSceneNodes() const pure virtual
Get pointers to this physics object's visual scene nodes.
Returns | vector of pointers to the object's visual scene nodes. |
---|
void esp:: physics:: PhysicsObjectBase:: setUserAttributes(core::config::Configuration::ptr attr)
This function will overwrite this object's existing user-defined attributes with attr
.
Parameters | |
---|---|
attr | A ptr to the user defined attributes specified for this object. |
void esp:: physics:: PhysicsObjectBase:: mergeUserAttributes(const core::config::Configuration::ptr& attr)
This function will merge this object's existing user-defined attributes with attr
by overwriting it with attr
.
Parameters | |
---|---|
attr | A ptr to the user defined attributes that are to be merged into this object's existing user-defined attributes. |
void esp:: physics:: PhysicsObjectBase:: setMarkerSets(metadata::attributes::MarkerSets::ptr attr)
This function will overwrite this object's existing MarkerSets attributes with attr
.
Parameters | |
---|---|
attr | A ptr to the MarkerSets attributes specified for this object. |
void esp:: physics:: PhysicsObjectBase:: mergeMarkerSets(const metadata::attributes::MarkerSets::ptr& attr)
This function will merge this object's existing MarkerSets attributes with attr
by overwriting it with attr
.
Parameters | |
---|---|
attr | A ptr to the user defined attributes specified for this object. with mergee into them. |
Magnum:: Vector3 esp:: physics:: PhysicsObjectBase:: getScale() const virtual
Get the scale of the object set during initialization.
Returns | The scaling for the object relative to its initially loaded meshes. |
---|
template<class T>
std:: shared_ptr<T> esp:: physics:: PhysicsObjectBase:: getInitObjectInstanceAttrCopyInternal() const protected
Accessed internally. Get an appropriately cast copy of the metadata::
Returns | A copy of the initialization template used to create this object instance or nullptr if no template exists. |
---|
template<class T>
std:: shared_ptr<const T> esp:: physics:: PhysicsObjectBase:: getInitObjectInstanceAttrInternal() const protected
Accessed internally. Get the metadata::
Returns | The initialization template used to create this object instance or nullptr if no template exists. |
---|
template<class T>
std:: shared_ptr<T> esp:: physics:: PhysicsObjectBase:: getCurrentObjectInstanceAttrInternal() protected
Accessed internally. Get an appropriately cast copy of the metadata::
Returns | A copy of the initialization template used to create this object instance or nullptr if no template exists. |
---|