class
BulletArticulatedObject
Base classes
- class ArticulatedObject
- An articulated rigid object (i.e. kinematic chain). Abstract class to be derived by physics simulator specific implementations.
Constructors, destructors, conversion operators
-
BulletArticulatedObject(scene::
SceneNode* rootNode, assets:: ResourceManager& resMgr, int objectId, std:: shared_ptr<btMultiBodyDynamicsWorld> bWorld, std:: shared_ptr<std:: map<const btCollisionObject*, int>> collisionObjToObjIds) - ~BulletArticulatedObject() override
Public functions
-
void initializeFromURDF(const std::
shared_ptr<metadata:: attributes:: ArticulatedObjectAttributes>& initAttributes, URDFImporter& u2b, const Magnum:: Matrix4& worldTransform, scene:: SceneNode* physicsNode) override - Initialize this ArticulatedObject from a parsed URDF stored in a URDFImporter. Creates a btMultiBody.
- void constructStaticRigidBaseObject()
- Construct a Static btRigidObject to act as a proxy collision object for the fixed base.
- void updateNodes(bool force = false) override
- update the SceneNode state to match the simulation state
-
auto getCurrentStateInstanceAttr() -> std::
shared_ptr<metadata:: attributes:: SceneAOInstanceAttributes> override - Return a metadata::
attributes:: SceneAOInstanceAttributes reflecting the current state of this Articulated Object. -
auto getRootLinearVelocity() const -> Mn::
Vector3 override - Get the linear velocity of the articulated object's root in the global frame.
-
void setRootLinearVelocity(const Mn::
Vector3& linVel) override - Set the linear velocity of the articulated object's root in the global frame.
-
auto getRootAngularVelocity() const -> Mn::
Vector3 override - Get the angular velocity (omega) of the articulated object's root in the global frame.
-
void setRootAngularVelocity(const Mn::
Vector3& angVel) override - Set the angular velocity (omega) of the articulated object's root in the global frame.
-
void setJointForces(const std::
vector<float>& forces) override - Set forces/torques for all joints indexed by degrees of freedom.
-
void addJointForces(const std::
vector<float>& forces) override - Add forces/torques to all joints indexed by degrees of freedom.
-
auto getJointForces() -> std::
vector<float> override - Get current forces/torques for all joints indexed by degrees of freedom.
-
void setJointVelocities(const std::
vector<float>& vels) override - Set velocities for all joints indexed by degrees of freedom.
-
auto getJointVelocities() -> std::
vector<float> override - Get current velocities for all joints indexed by degrees of freedom.
-
void setJointPositions(const std::
vector<float>& positions) override - Set positions for all joints.
-
auto getJointPositions() -> std::
vector<float> override - Get positions for all joints.
-
auto getJointMotorTorques(double fixedTimeStep) -> std::
vector<float> override - Get the torques on each joint.
-
auto getJointPositionLimits() -> std::
pair<std:: vector<float>, std:: vector<float>> override - Get position limits for all joints. (lower, upper)
-
void addArticulatedLinkForce(int linkId,
Magnum::
Vector3 force) override - Add linear force to a link's COM specified in the global frame.
- auto getArticulatedLinkFriction(int linkId) -> float override
- Get the friction coefficient for a link.
- void setArticulatedLinkFriction(int linkId, float friction) override
- Set the friction coefficient for a link.
- auto getLinkJointType(int linkId) const -> JointType override
- Get the type of the link's parent joint.
- auto getLinkDoFOffset(int linkId) const -> int override
- Get the starting position for this link's parent joint in the global DoFs array.
- auto getLinkNumDoFs(int linkId) const -> int override
- Get the number of DoFs for this link's parent joint.
- auto getLinkJointPosOffset(int linkId) const -> int override
- Get the starting position for this link's parent joint in the global positions array.
- auto getLinkNumJointPos(int linkId) const -> int override
- Get the number of positions for this link's parent joint.
- void reset() override
- reset the articulated object state by clearing forces and zeroing positions and velocities.
- void setActive(bool active) override
- Set an object as being actively simulated or sleeping.
- auto isActive() const -> bool override
- Check whether object is being actively simulated, or sleeping.
- auto getCanSleep() -> bool override
- Check if this object can be de-activated (i.e. sleep).
- void setMotionType(MotionType mt) override
- Set the MotionType of the object.
- auto contactTest() -> bool override
- Return result of a discrete contact test between the object and collision world.
- void clampJointLimits() override
- clamp current pose to joint limits
- void overrideCollisionGroup(CollisionGroup group) override
- Manually set the collision group for all links of the object.
- auto supportsSingleDofJointMotor(int linkIx) const -> bool
- auto createJointMotor(int linkIndex, const JointMotorSettings& settings) -> int override
- Create a new JointMotor from a JointMotorSettings.
- void removeJointMotor(int motorId) override
- Remove and destroy a joint motor.
- void updateJointMotor(int motorId, const JointMotorSettings& settings) override
- Update a JointMotor with new settings.
-
auto createMotorsForAllDofs(const JointMotorSettings& settings = JointMotorSettings()) -> std::
unordered_map<int, int> override - Create a new set of default JointMotors for all valid dofs in an ArticulatedObject.
-
void updateAllMotorTargets(const std::
vector<float>& stateTargets, bool velocities = false) override - Update all motors targets for this object's joints which support motors (Revolute, Prismatic, Spherical) from a state array.
- void resetStateFromSceneInstanceAttr() override
- Set or reset the articulated object's state using the object's specified
sceneAOInstanceAttributes_
(down cast in method).
Public variables
-
std::
unique_ptr<btMultiBody> btMultiBody_ - The Bullet multibody structure.
Protected functions
-
void setRootState(const Magnum::
Matrix4& state) override - Called internally from syncPose() Used to update physics constructs when kinematic transformations are performed manually. See esp::
physics:: PhysicsObjectBase for the transformations. - void updateKinematicState()
- void setCollisionObjectsActivateState(bool activate) const
Protected variables
- int nextJointMotorId_
-
std::
unordered_map<int, std:: unique_ptr<btMultiBodyJointMotor>> articulatedJointMotors -
std::
unordered_map<int, std:: unique_ptr<btMultiBodySphericalJointMotor>> articulatedSphericalJointMotors -
std::
unordered_map<int, JointLimitConstraintInfo> jointLimitConstraints_ - maps local link id to parent joint's limit constraint
- btAlignedObjectArray<btQuaternion> scratch_q_
- btAlignedObjectArray<btVector3> scratch_m_
-
std::
shared_ptr<btMultiBodyDynamicsWorld> bWorld_ - The containing Bullet world.
-
std::
unique_ptr<btCompoundShape> bFixedObjectShape_ - The collision shape for the fixed base rigid object.
-
std::
unique_ptr<btRigidBody> bFixedObjectRigidBody_ - A proxy rigid object to replace fixed base links as a perf optimization.
-
std::
map<int, std:: unique_ptr<btCompoundShape>> linkCompoundShapes_ -
std::
map<int, std:: vector<std:: unique_ptr<btCollisionShape>>> linkChildShapes_ -
std::
shared_ptr<std:: map<const btCollisionObject*, int>> collisionObjToObjIds_
Function documentation
void esp:: physics:: BulletArticulatedObject:: initializeFromURDF(const std:: shared_ptr<metadata:: attributes:: ArticulatedObjectAttributes>& initAttributes,
URDFImporter& u2b,
const Magnum:: Matrix4& worldTransform,
scene:: SceneNode* physicsNode) override
Initialize this ArticulatedObject from a parsed URDF stored in a URDFImporter. Creates a btMultiBody.
Parameters | |
---|---|
initAttributes | The ArticulatedObjectAttributes used to build this ArticulatedObject. |
u2b | The BulletURDFImporter 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. |
void esp:: physics:: BulletArticulatedObject:: constructStaticRigidBaseObject()
Construct a Static btRigidObject to act as a proxy collision object for the fixed base.
This optimization reduces the collision island size for articulated objects with heavy branching (e.g. a counter with many drawers) resulting in better sleeping behavior (e.g. contact with the countertop should not activate all drawers and contained objects).
To utilize this feature, the object URDF should mark fixed link collision shapes as part of the Static collision group (e.g. <collision group="2">
)
std:: shared_ptr<metadata:: attributes:: SceneAOInstanceAttributes> esp:: physics:: BulletArticulatedObject:: getCurrentStateInstanceAttr() override
Return a metadata::
Returns | a SceneAOInstanceAttributes reflecting this Articulated Object's current state |
---|
Mn:: Vector3 esp:: physics:: BulletArticulatedObject:: getRootLinearVelocity() const override
Get the linear velocity of the articulated object's root in the global frame.
Returns | The root linear velocity. |
---|
void esp:: physics:: BulletArticulatedObject:: setRootLinearVelocity(const Mn:: Vector3& linVel) override
Set the linear velocity of the articulated object's root in the global frame.
Parameters | |
---|---|
linVel | The root linear velocity. |
Mn:: Vector3 esp:: physics:: BulletArticulatedObject:: getRootAngularVelocity() const override
Get the angular velocity (omega) of the articulated object's root in the global frame.
Returns | The root angular velocity (omega). |
---|
void esp:: physics:: BulletArticulatedObject:: setRootAngularVelocity(const Mn:: Vector3& angVel) override
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:: BulletArticulatedObject:: setJointForces(const std:: vector<float>& forces) override
Set forces/torques for all joints indexed by degrees of freedom.
Parameters | |
---|---|
forces | The desired joint forces/torques. |
Bullet clears joint forces/torques with each simulation step.
void esp:: physics:: BulletArticulatedObject:: addJointForces(const std:: vector<float>& forces) override
Add forces/torques to all joints indexed by degrees of freedom.
Parameters | |
---|---|
forces | The desired joint forces/torques to add. |
Bullet clears joint forces/torques with each simulation step.
std:: vector<float> esp:: physics:: BulletArticulatedObject:: getJointForces() override
Get current forces/torques for all joints indexed by degrees of freedom.
Returns | The current joint forces/torques. |
---|
Bullet clears joint forces/torques with each simulation step.
void esp:: physics:: BulletArticulatedObject:: setJointVelocities(const std:: vector<float>& vels) override
Set velocities for all joints indexed by degrees of freedom.
Parameters | |
---|---|
vels | The desired joint velocities. |
std:: vector<float> esp:: physics:: BulletArticulatedObject:: getJointVelocities() override
Get current velocities for all joints indexed by degrees of freedom.
Returns | The current joint velocities. |
---|
void esp:: physics:: BulletArticulatedObject:: setJointPositions(const std:: vector<float>& positions) override
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:: BulletArticulatedObject:: getJointPositions() override
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:: BulletArticulatedObject:: getJointMotorTorques(double fixedTimeStep) override
Get the torques on each joint.
Parameters | |
---|---|
fixedTimeStep | The physics timestep used by the simulator. Necessary to convert impulse into torque. |
Returns | Array of torques on each joint |
std:: pair<std:: vector<float>, std:: vector<float>> esp:: physics:: BulletArticulatedObject:: getJointPositionLimits() override
Get position limits for all joints. (lower, upper)
Returns | The active joint position limits as a pair of vectors (lower, upper). When no limit is set, entry is inf or -inf. |
---|
void esp:: physics:: BulletArticulatedObject:: addArticulatedLinkForce(int linkId,
Magnum:: Vector3 force) override
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:: BulletArticulatedObject:: getArticulatedLinkFriction(int linkId) override
Get the friction coefficient for a link.
Parameters | |
---|---|
linkId | The link's index. |
Returns | The link's friction coefficient. |
void esp:: physics:: BulletArticulatedObject:: setArticulatedLinkFriction(int linkId,
float friction) override
Set the friction coefficient for a link.
Parameters | |
---|---|
linkId | The link's index. |
friction | The link's friction coefficient. |
JointType esp:: physics:: BulletArticulatedObject:: getLinkJointType(int linkId) const override
Get the type of the link's parent joint.
Parameters | |
---|---|
linkId | The link's index. |
Returns | The link's parent joint's type. |
int esp:: physics:: BulletArticulatedObject:: getLinkDoFOffset(int linkId) const override
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:: BulletArticulatedObject:: getLinkNumDoFs(int linkId) const override
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:: BulletArticulatedObject:: getLinkJointPosOffset(int linkId) const override
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:: BulletArticulatedObject:: getLinkNumJointPos(int linkId) const override
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. |
void esp:: physics:: BulletArticulatedObject:: setActive(bool active) override
Set an object as being actively simulated or sleeping.
Parameters | |
---|---|
active | Whether to activate or sleep the object |
bool esp:: physics:: BulletArticulatedObject:: isActive() const override
Check whether object is being actively simulated, or sleeping.
Returns | true if active, false otherwise. |
---|
bool esp:: physics:: BulletArticulatedObject:: getCanSleep() override
Check if this object can be de-activated (i.e. sleep).
Returns | Whether or not the object is able to deactivate. |
---|
void esp:: physics:: BulletArticulatedObject:: setMotionType(MotionType mt) override
Set the MotionType of the object.
Parameters | |
---|---|
mt | The desired MotionType. |
Dynamic state is integrated by physics simulator. Kinematic state is manually set by user. Static state should not be changed. Object can be added to NavMesh.
bool esp:: physics:: BulletArticulatedObject:: contactTest() override
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:: BulletArticulatedObject:: overrideCollisionGroup(CollisionGroup group) override
Manually set the collision group for all links of the object.
Parameters | |
---|---|
group | The desired CollisionGroup for the object. |
bool esp:: physics:: BulletArticulatedObject:: supportsSingleDofJointMotor(int linkIx) const
Bullet supports vel/pos control joint motors for revolute and prismatic joints (1 Dof) This is the suggested way to implement friction/damping at dof level
int esp:: physics:: BulletArticulatedObject:: createJointMotor(int linkIndex,
const JointMotorSettings& settings) override
Create a new JointMotor from a JointMotorSettings.
Parameters | |
---|---|
linkIndex | the index of the link for which the parent joint will have a motor attached |
settings | The settings for the joint motor. Must have JointMotorType correctly configured for the target joint. |
Returns | The motorId for the new joint motor |
Note: No base implementation. See BulletArticulatedObject.
std:: unordered_map<int, int> esp:: physics:: BulletArticulatedObject:: createMotorsForAllDofs(const JointMotorSettings& settings = JointMotorSettings()) override
Create a new set of default JointMotors for all valid dofs in an ArticulatedObject.
Returns | A map of motorIds to link/joint indices for the new motors. |
---|
Note: No base implementation. See BulletArticulatedObject.
void esp:: physics:: BulletArticulatedObject:: updateAllMotorTargets(const std:: vector<float>& stateTargets,
bool velocities = false) override
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 joints which don't support JointMotors.
Note: No base implementation. See BulletArticulatedObject.
void esp:: physics:: BulletArticulatedObject:: updateKinematicState() protected
Performs forward kinematics, updates collision object states and broadphase aabbs for the object. Do this with manual state setters.
void esp:: physics:: BulletArticulatedObject:: setCollisionObjectsActivateState(bool activate) const protected
Instantly set activation state of the base and link collision objects, otherwise deferred to simulation time