esp::physics::ArticulatedObject class

An articulated rigid object (i.e. kinematic chain). Abstract class to be derived by physics simulator specific implementations.

Base classes

class PhysicsObjectBase

Derived classes

class BulletArticulatedObject

Constructors, destructors, conversion operators

ArticulatedObject(scene::SceneNode* rootNode, assets::ResourceManager& resMgr, int objectId)
~ArticulatedObject() override

Public functions

auto getGlobalScale() const -> float
Get the uniform global scaling applied to this object during import.
auto getLinkSceneNode(int linkId = -1) const -> const scene::SceneNode&
Get a const reference to an ArticulatedLink SceneNode for info query purposes.
auto getLinkVisualSceneNodes(int linkId = -1) const -> std::vector<scene::SceneNode*>
Get pointers to a link's visual SceneNodes.
auto getVisualSceneNodes() const -> std::vector<scene::SceneNode*> override
Get pointers to all visual SceneNodes associated to this ArticulatedObject.
void initializeFromURDF(const std::shared_ptr<metadata::attributes::ArticulatedObjectAttributes>& initAttributes, URDFImporter& urdfImporter, const Magnum::Matrix4& worldTransform, scene::SceneNode* physicsNode) virtual
Initialize this ArticulatedObject from a parsed URDF stored in a URDFImporter.
auto getLink(int id) -> ArticulatedLink&
Get a link by index.
auto getNumLinks() const -> int
Get the number of links for this object (not including the base).
auto getLinkIds() const -> std::vector<int>
Get a list of link ids, not including the base (-1).
auto getLinkIdsWithBase() const -> std::vector<int>
Get a list of link ids including the base (-1).
auto getLinkObjectIds() const -> std::unordered_map<int, int>
Get a map of object ids to link ids.
void setJointForces(const std::vector<float>& forces) virtual
Set forces/torques for all joints indexed by degrees of freedom.
void addJointForces(const std::vector<float>& forces) virtual
Add forces/torques to all joints indexed by degrees of freedom.
auto getJointForces() -> std::vector<float> virtual
Get current forces/torques for all joints indexed by degrees of freedom.
void setJointVelocities(const std::vector<float>& vels) virtual
Set velocities for all joints indexed by degrees of freedom.
auto getJointVelocities() -> std::vector<float> virtual
Get current velocities for all joints indexed by degrees of freedom.
void setJointPositions(const std::vector<float>& positions) virtual
Set positions for all joints.
auto getJointPositions() -> std::vector<float> virtual
Get positions for all joints.
auto getJointMotorTorques(double fixedTimeStep) -> std::vector<float> virtual
Get the torques on each joint.
auto getJointPositionLimits() -> std::pair<std::vector<float>, std::vector<float>> virtual
Get position limits for all joints.
auto getRootLinearVelocity() const -> Mn::Vector3 virtual
Get the linear velocity of the articulated object's root in the global frame.
void setRootLinearVelocity(const Mn::Vector3& linVel) virtual
Set the linear velocity of the articulated object's root in the global frame.
auto getRootAngularVelocity() const -> Mn::Vector3 virtual
Get the angular velocity (omega) of the articulated object's root in the global frame.
void setRootAngularVelocity(const Mn::Vector3& angVel) virtual
Set the angular velocity (omega) of the articulated object's root in the global frame.
void addArticulatedLinkForce(int linkId, Magnum::Vector3 force) virtual
Add linear force to a link's COM specified in the global frame.
auto getArticulatedLinkFriction(int linkId) -> float virtual
Get the friction coefficient for a link.
void setArticulatedLinkFriction(int linkId, float friction) virtual
Set the friction coefficient for a link.
auto getLinkJointType(int linkId) const -> JointType virtual
Get the type of the link's parent joint.
auto getLinkJointName(int linkId) const -> std::string virtual
Get the name of the link's parent joint.
auto getLinkName(int linkId) const -> std::string virtual
Get the name of the link.
auto getLinkDoFOffset(int linkId) const -> int virtual
Get the starting position for this link's parent joint in the global DoFs array.
auto getLinkNumDoFs(int linkId) const -> int virtual
Get the number of DoFs for this link's parent joint.
auto getLinkJointPosOffset(int linkId) const -> int virtual
Get the starting position for this link's parent joint in the global positions array.
auto getLinkNumJointPos(int linkId) const -> int virtual
Get the number of positions for this link's parent joint.
void reset() virtual
reset the articulated object state by clearing forces and zeroing positions and velocities. Does not change root state.
auto getCanSleep() -> bool virtual
Check if this object can be de-activated (i.e. sleep).
void setAutoClampJointLimits(bool autoClamp)
Set whether articulated object state is automatically clamped to configured joint limits before physics simulation.
auto getAutoClampJointLimits() const -> bool
Query whether articulated object state is automatically clamped to configured joint limits before physics simulation.
void clampJointLimits() virtual
Clamp current pose to joint limits. See derived implementations.
auto createJointMotor(const int index, const JointMotorSettings& settings) -> int virtual
Create a new JointMotor from a JointMotorSettings.
void removeJointMotor(const int motorId) virtual
Remove and destroy a joint motor.
auto getJointMotorSettings(const int motorId) -> JointMotorSettings virtual
Get a copy of the JointMotorSettings for an existing motor.
void updateJointMotor(const int motorId, const JointMotorSettings& settings) virtual
Update a JointMotor with new settings.
auto getExistingJointMotors() -> std::unordered_map<int, int> virtual
Query a map of motorIds -> links/joints for all active JointMotors.
auto createMotorsForAllDofs(const JointMotorSettings& settings = JointMotorSettings()) -> std::unordered_map<int, int> virtual
Create a new set of default JointMotors for all valid dofs in an ArticulatedObject.
void updateAllMotorTargets(const std::vector<float>& stateTargets, bool velocities = false) virtual
Update all motors targets for this object's joints which support motors (Revolute, Prismatic, Spherical) from a state array.
auto getInitObjectInstanceAttr() const -> std::shared_ptr<const metadata::attributes::SceneAOInstanceAttributes>
Returns the metadata::attributes::SceneAOInstanceAttributes used to place this Articulated Object initially in the scene.
auto getCurrentStateInstanceAttr() -> std::shared_ptr<metadata::attributes::SceneAOInstanceAttributes> virtual
Return a metadata::attributes::SceneAOInstanceAttributes reflecting the current state of this Articulated Object. Note : base PhysicsManager implementation does not support state changes on ArticulatedObjects, so no change will occur from initialization InstanceAttributes.
auto getInitializationAttributes() const -> std::shared_ptr<metadata::attributes::ArticulatedObjectAttributes>
Get a copy of the template used to initialize this object.

Public variables

std::unordered_map<int, int> objectIdToLinkId_
map PhysicsManager objectId to local multibody linkId

Protected functions

void syncPose() override
Used to synchronize simulator's notion of the object state after it was changed kinematically. Must be called automatically on kinematic updates. For ArticulatedObjects, the transformation of the root node is used to transform the root physical constructs.
void setRootState(const Magnum::Matrix4& state) virtual
Called internally from syncPose() Used to update physics constructs when kinematic transformations are performed manually. See esp::physics::PhysicsObjectBase for the transformations.

Protected variables

std::map<int, ArticulatedLink::uptr> links_
map linkId to ArticulatedLink
ArticulatedLink::uptr baseLink_
link object for the AO base
std::unordered_map<int, JointMotor::uptr> jointMotors_
map motorId to JointMotor
bool autoClampJointLimits_
float globalScale_
Cache the global scaling from the source model. Set during import.

Function documentation

float esp::physics::ArticulatedObject::getGlobalScale() const

Get the uniform global scaling applied to this object during import.

Returns The global scaling applied to the object.

const scene::SceneNode& esp::physics::ArticulatedObject::getLinkSceneNode(int linkId = -1) const

Get a const reference to an ArticulatedLink SceneNode for info query purposes.

Parameters
linkId The ArticulatedLink ID or -1 for the baseLink.
Returns Const reference to the SceneNode.

std::vector<scene::SceneNode*> esp::physics::ArticulatedObject::getLinkVisualSceneNodes(int linkId = -1) const

Get pointers to a link's visual SceneNodes.

Parameters
linkId The ArticulatedLink ID or -1 for the baseLink.
Returns vector of pointers to the link's visual scene nodes.

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

Get pointers to all visual SceneNodes associated to this ArticulatedObject.

Returns vector of pointers to base and all links' visual scene nodes.

void esp::physics::ArticulatedObject::initializeFromURDF(const std::shared_ptr<metadata::attributes::ArticulatedObjectAttributes>& initAttributes, URDFImporter& urdfImporter, const Magnum::Matrix4& worldTransform, scene::SceneNode* physicsNode) virtual

Initialize this ArticulatedObject from a parsed URDF stored in a URDFImporter.

Parameters
initAttributes The ArticulatedObjectAttributes used to build this ArticulatedObject.
urdfImporter The URDFImporter which will initialize this object from a parsed URDF file.
worldTransform Desired global root state of the ArticulatedObject.
physicsNode The parent node of this object.

ArticulatedLink& esp::physics::ArticulatedObject::getLink(int id)

Get a link by index.

Parameters
id The id of the desired link. -1 for base link.
Returns The desired link.

int esp::physics::ArticulatedObject::getNumLinks() const

Get the number of links for this object (not including the base).

Returns The number of non-base links.

std::vector<int> esp::physics::ArticulatedObject::getLinkIds() const

Get a list of link ids, not including the base (-1).

Returns A list of link ids for this object.

std::vector<int> esp::physics::ArticulatedObject::getLinkIdsWithBase() const

Get a list of link ids including the base (-1).

Returns A list of link ids for this object.

std::unordered_map<int, int> esp::physics::ArticulatedObject::getLinkObjectIds() const

Get a map of object ids to link ids.

Returns A a map of Habitat object ids to link ids for this AO's links.

void esp::physics::ArticulatedObject::setJointForces(const std::vector<float>& forces) virtual

Set forces/torques for all joints indexed by degrees of freedom.

Parameters
forces The desired joint forces/torques.

void esp::physics::ArticulatedObject::addJointForces(const std::vector<float>& forces) virtual

Add forces/torques to all joints indexed by degrees of freedom.

Parameters
forces The desired joint forces/torques to add.

std::vector<float> esp::physics::ArticulatedObject::getJointForces() virtual

Get current forces/torques for all joints indexed by degrees of freedom.

Returns The current joint forces/torques.

void esp::physics::ArticulatedObject::setJointVelocities(const std::vector<float>& vels) virtual

Set velocities for all joints indexed by degrees of freedom.

Parameters
vels The desired joint velocities.

std::vector<float> esp::physics::ArticulatedObject::getJointVelocities() virtual

Get current velocities for all joints indexed by degrees of freedom.

Returns The current joint velocities.

void esp::physics::ArticulatedObject::setJointPositions(const std::vector<float>& positions) virtual

Set positions for all joints.

Parameters
positions The desired joint positions.

Note that positions are not indexed by DoF because some joints (spherical) have a different number of DoFs from positions. For spherical joints, a block of 4 position values should specify the state as a unit quaternion (x y z w).

std::vector<float> esp::physics::ArticulatedObject::getJointPositions() virtual

Get positions for all joints.

Returns The current joint positions.

Note that positions are not indexed by DoF because some joints (spherical) have a different number of DoFs from positions. For spherical joints, a block of 4 position values should specify the state as a unit quaternion (x y z w).

std::vector<float> esp::physics::ArticulatedObject::getJointMotorTorques(double fixedTimeStep) virtual

Get the torques on each joint.

Parameters
fixedTimeStep The physics timestep used by the simulator. Necessary to convert impulse into torque.
Returns Vector of torques on each joint

std::pair<std::vector<float>, std::vector<float>> esp::physics::ArticulatedObject::getJointPositionLimits() virtual

Get position limits for all joints.

Returns The active joint position limits. Default implementation returns empty list.

Mn::Vector3 esp::physics::ArticulatedObject::getRootLinearVelocity() const virtual

Get the linear velocity of the articulated object's root in the global frame.

Returns The root linear velocity.

void esp::physics::ArticulatedObject::setRootLinearVelocity(const Mn::Vector3& linVel) virtual

Set the linear velocity of the articulated object's root in the global frame.

Parameters
linVel The root linear velocity.

Mn::Vector3 esp::physics::ArticulatedObject::getRootAngularVelocity() const virtual

Get the angular velocity (omega) of the articulated object's root in the global frame.

Returns The root angular velocity (omega).

void esp::physics::ArticulatedObject::setRootAngularVelocity(const Mn::Vector3& angVel) virtual

Set the angular velocity (omega) of the articulated object's root in the global frame.

Parameters
angVel The root angular velocity (omega).

void esp::physics::ArticulatedObject::addArticulatedLinkForce(int linkId, Magnum::Vector3 force) virtual

Add linear force to a link's COM specified in the global frame.

Parameters
linkId The link's index.
force The desired force to add.

float esp::physics::ArticulatedObject::getArticulatedLinkFriction(int linkId) virtual

Get the friction coefficient for a link.

Parameters
linkId The link's index.
Returns The link's friction coefficient.

void esp::physics::ArticulatedObject::setArticulatedLinkFriction(int linkId, float friction) virtual

Set the friction coefficient for a link.

Parameters
linkId The link's index.
friction The link's friction coefficient.

JointType esp::physics::ArticulatedObject::getLinkJointType(int linkId) const virtual

Get the type of the link's parent joint.

Parameters
linkId The link's index.
Returns The link's parent joint's type.

std::string esp::physics::ArticulatedObject::getLinkJointName(int linkId) const virtual

Get the name of the link's parent joint.

Parameters
linkId The link's index.
Returns The link's parent joint's name.

std::string esp::physics::ArticulatedObject::getLinkName(int linkId) const virtual

Get the name of the link.

Parameters
linkId The link's index. -1 for base link.
Returns The link's name.

int esp::physics::ArticulatedObject::getLinkDoFOffset(int linkId) const virtual

Get the starting position for this link's parent joint in the global DoFs array.

Parameters
linkId The link's index.
Returns The link's starting DoF index.

int esp::physics::ArticulatedObject::getLinkNumDoFs(int linkId) const virtual

Get the number of DoFs for this link's parent joint.

Parameters
linkId The link's index.
Returns The number of DoFs for this link's parent joint.

int esp::physics::ArticulatedObject::getLinkJointPosOffset(int linkId) const virtual

Get the starting position for this link's parent joint in the global positions array.

Parameters
linkId The link's index.
Returns The link's starting position index.

int esp::physics::ArticulatedObject::getLinkNumJointPos(int linkId) const virtual

Get the number of positions for this link's parent joint.

Parameters
linkId The link's index.
Returns The number of positions for this link's parent joint.

bool esp::physics::ArticulatedObject::getCanSleep() virtual

Check if this object can be de-activated (i.e. sleep).

Returns Whether or not the object is able to deactivate.

int esp::physics::ArticulatedObject::createJointMotor(const int index, const JointMotorSettings& settings) virtual

Create a new JointMotor from a JointMotorSettings.

Parameters
index DoF (for revolute or prismatic joints) or Link (spherical joints)
settings The settings for the joint motor. Must have JointMotorType correctly configured.
Returns The motorId for the new joint motor or ID_UNDEFINED (-1) if failed.

Note: No base implementation. See BulletArticulatedObject.

std::unordered_map<int, int> esp::physics::ArticulatedObject::createMotorsForAllDofs(const JointMotorSettings& settings = JointMotorSettings()) virtual

Create a new set of default JointMotors for all valid dofs in an ArticulatedObject.

Returns A map motorIds to link/joint indices for the new motors.

Note: No base implementation. See BulletArticulatedObject.

void esp::physics::ArticulatedObject::updateAllMotorTargets(const std::vector<float>& stateTargets, bool velocities = false) virtual

Update all motors targets for this object's joints which support motors (Revolute, Prismatic, Spherical) from a state array.

Parameters
stateTargets Full length joint position or velocity array for this object.
velocities Whether to interpret stateTargets as velocities or positions.

By default, state is interpreted as position targets unless velocities is specified. Expected input is the full length position or velocity array for this object. This function will safely skip states for jointa which don't support JointMotors.

Note: No base implementation. See BulletArticulatedObject.

std::shared_ptr<const metadata::attributes::SceneAOInstanceAttributes> esp::physics::ArticulatedObject::getInitObjectInstanceAttr() const

Returns the metadata::attributes::SceneAOInstanceAttributes used to place this Articulated Object initially in the scene.

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

std::shared_ptr<metadata::attributes::SceneAOInstanceAttributes> esp::physics::ArticulatedObject::getCurrentStateInstanceAttr() virtual

Return a metadata::attributes::SceneAOInstanceAttributes reflecting the current state of this Articulated Object. Note : base PhysicsManager implementation does not support state changes on ArticulatedObjects, so no change will occur from initialization InstanceAttributes.

Returns a SceneAOInstanceAttributes reflecting this Articulated Object's current state

std::shared_ptr<metadata::attributes::ArticulatedObjectAttributes> esp::physics::ArticulatedObject::getInitializationAttributes() const

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

Returns A copy of the esp::metadata::attributes::ArticulatedObjectAttributes template used to create this object.

Variable documentation

bool esp::physics::ArticulatedObject::autoClampJointLimits_ protected

if true, automatically clamp dofs to joint limits before physics simulation steps