Base class for all joints. More...
#include <physics/physics.hh>
Inherits Base.
Inherited by BulletJoint, DARTJoint, ODEJoint, and SimbodyJoint.
Public Types | |
enum | Attribute { FUDGE_FACTOR, SUSPENSION_ERP, SUSPENSION_CFM, STOP_ERP, STOP_CFM, ERP, CFM, FMAX, VEL, HI_STOP, LO_STOP } |
Joint attribute types. More... | |
enum | EntityType { BASE = 0x00000000, ENTITY = 0x00000001, MODEL = 0x00000002, LINK = 0x00000004, COLLISION = 0x00000008, ACTOR = 0x00000016, LIGHT = 0x00000010, VISUAL = 0x00000020, JOINT = 0x00000040, BALL_JOINT = 0x00000080, HINGE2_JOINT = 0x00000100, HINGE_JOINT = 0x00000200, SLIDER_JOINT = 0x00000400, SCREW_JOINT = 0x00000800, UNIVERSAL_JOINT = 0x00001000, GEARBOX_JOINT = 0x00002000, FIXED_JOINT = 0x00004000, SHAPE = 0x00010000, BOX_SHAPE = 0x00020000, CYLINDER_SHAPE = 0x00040000, HEIGHTMAP_SHAPE = 0x00080000, MAP_SHAPE = 0x00100000, MULTIRAY_SHAPE = 0x00200000, RAY_SHAPE = 0x00400000, PLANE_SHAPE = 0x00800000, SPHERE_SHAPE = 0x01000000, MESH_SHAPE = 0x02000000, POLYLINE_SHAPE = 0x04000000, SENSOR_COLLISION = 0x10000000 } |
Unique identifiers for all entity types. More... | |
Public Member Functions | |
Joint (BasePtr _parent) | |
Constructor. More... | |
virtual | ~Joint () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
virtual void | ApplyStiffnessDamping () |
Callback to apply spring stiffness and viscous damping effects to joint. More... | |
virtual bool | AreConnected (LinkPtr _one, LinkPtr _two) const =0 |
Determines of the two bodies are connected by a joint. More... | |
virtual void | Attach (LinkPtr _parent, LinkPtr _child) |
Attach the two bodies with this joint. More... | |
virtual void | CacheForceTorque () |
Cache Joint Force Torque Values if necessary for physics engine. More... | |
double | CheckAndTruncateForce (unsigned int _index, double _effort) |
check if the force against velocityLimit and effortLimit, truncate if necessary. More... | |
template<typename T > | |
event::ConnectionPtr | ConnectJointUpdate (T _subscriber) |
Connect a boost::slot the the joint update signal. More... | |
virtual void | Detach () |
Detach this joint from all links. More... | |
void | DisconnectJointUpdate (event::ConnectionPtr &_conn) |
Disconnect a boost::slot the the joint update signal. More... | |
virtual void | FillMsg (msgs::Joint &_msg) |
Fill a joint message. More... | |
virtual void | Fini () |
Finialize the object. More... | |
virtual math::Vector3 | GetAnchor (unsigned int _index) const =0 |
Get the anchor point. More... | |
math::Pose | GetAnchorErrorPose () const |
Get pose offset between anchor pose on child and parent, expressed in the parent link frame. More... | |
math::Angle | GetAngle (unsigned int _index) const |
Get the angle of rotation of an axis(index) More... | |
virtual unsigned int | GetAngleCount () const =0 |
Get the angle count. More... | |
math::Quaternion | GetAxisFrame (unsigned int _index) const |
Get orientation of reference frame for specified axis, relative to world frame. More... | |
math::Quaternion | GetAxisFrameOffset (unsigned int _index) const |
Get orientation of joint axis reference frame relative to joint frame. More... | |
BasePtr | GetByName (const std::string &_name) |
Get by name. More... | |
BasePtr | GetChild (unsigned int _i) const |
Get a child by index. More... | |
BasePtr | GetChild (const std::string &_name) |
Get a child by name. More... | |
LinkPtr | GetChild () const |
Get the child link. More... | |
unsigned int | GetChildCount () const |
Get the number of children. More... | |
double | GetDamping (unsigned int _index) |
Returns the current joint damping coefficient. More... | |
virtual double | GetEffortLimit (unsigned int _index) |
Get the effort limit on axis(index). More... | |
virtual double | GetForce (unsigned int _index) |
virtual JointWrench | GetForceTorque (unsigned int _index)=0 |
get internal force and torque values at a joint. More... | |
virtual math::Vector3 | GetGlobalAxis (unsigned int _index) const =0 |
Get the axis of rotation in global cooridnate frame. More... | |
virtual math::Angle | GetHighStop (unsigned int _index)=0 |
Get the high stop of an axis(index). More... | |
uint32_t | GetId () const |
Return the ID of this entity. More... | |
double | GetInertiaRatio (const unsigned int _index) const |
Computes moment of inertia (MOI) across a specified joint axis. More... | |
double | GetInertiaRatio (const math::Vector3 &_axis) const |
Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame. More... | |
math::Pose | GetInitialAnchorPose () const |
Get initial Anchor Pose specified by model <joint><pose>...</pose></joint> More... | |
virtual LinkPtr | GetJointLink (unsigned int _index) const =0 |
Get the link to which the joint is attached according the _index. More... | |
virtual math::Vector3 | GetLinkForce (unsigned int _index) const =0 |
Get the forces applied to the center of mass of a physics::Link due to the existence of this Joint. More... | |
virtual math::Vector3 | GetLinkTorque (unsigned int _index) const =0 |
Get the torque applied to the center of mass of a physics::Link due to the existence of this Joint. More... | |
math::Vector3 | GetLocalAxis (unsigned int _index) const |
Get the axis of rotation. More... | |
math::Angle | GetLowerLimit (unsigned int _index) const |
: get the joint upper limit (replaces GetLowStop and GetHighStop) More... | |
virtual math::Angle | GetLowStop (unsigned int _index)=0 |
Get the low stop of an axis(index). More... | |
msgs::Joint::Type | GetMsgType () const |
Get the joint type as msgs::Joint::Type. More... | |
std::string | GetName () const |
Return the name of the entity. More... | |
virtual double | GetParam (const std::string &_key, unsigned int _index) |
Get a non-generic parameter for the joint. More... | |
LinkPtr | GetParent () const |
Get the parent link. More... | |
int | GetParentId () const |
Return the ID of the parent. More... | |
math::Pose | GetParentWorldPose () const |
Get anchor pose on parent link relative to world frame. More... | |
bool | GetSaveable () const |
Get whether the object should be "saved", when the user selects to save the world to xml. More... | |
std::string | GetScopedName (bool _prependWorldName=false) const |
Return the name of this entity with the model scope model1::...::modelN::entityName. More... | |
virtual const sdf::ElementPtr | GetSDF () |
Get the SDF values for the object. More... | |
double | GetSpringReferencePosition (unsigned int _index) const |
Get joint spring reference position. More... | |
double | GetStiffness (unsigned int _index) |
Returns the current joint spring stiffness coefficient. More... | |
double | GetStopDissipation (unsigned int _index) const |
Get joint stop dissipation. More... | |
double | GetStopStiffness (unsigned int _index) const |
Get joint stop stiffness. More... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
math::Angle | GetUpperLimit (unsigned int _index) const |
: get the joint lower limit (replacee GetLowStop and GetHighStop) More... | |
virtual double | GetVelocity (unsigned int _index) const =0 |
Get the rotation rate of an axis(index) More... | |
virtual double | GetVelocityLimit (unsigned int _index) |
Get the velocity limit on axis(index). More... | |
const WorldPtr & | GetWorld () const |
Get the World this object is in. More... | |
double | GetWorldEnergyPotentialSpring (unsigned int _index) const |
Returns this joint's spring potential energy, based on the reference position of the spring. More... | |
math::Pose | GetWorldPose () const |
Get pose of joint frame relative to world frame. More... | |
bool | HasType (const EntityType &_t) const |
Returns true if this object's type definition has the given type. More... | |
virtual void | Init () |
Initialize a joint. More... | |
bool | IsSelected () const |
True if the entity is selected by the user. More... | |
void | Load (LinkPtr _parent, LinkPtr _child, const math::Pose &_pose) |
Set pose, parent and child links of a physics::Joint. More... | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load physics::Joint from a SDF sdf::Element. More... | |
bool | operator== (const Base &_ent) const |
Returns true if the entities are the same. More... | |
void | Print (const std::string &_prefix) |
Print this object to screen via gzmsg. More... | |
virtual void | RemoveChild (unsigned int _id) |
Remove a child from this entity. More... | |
void | RemoveChild (const std::string &_name) |
Remove a child by name. More... | |
void | RemoveChild (physics::BasePtr _child) |
Remove a child by pointer. More... | |
void | RemoveChildren () |
Remove all children. More... | |
virtual void | Reset () |
Reset the joint. More... | |
virtual void | Reset (Base::EntityType _resetType) |
Calls recursive Reset on one of the Base::EntityType's. More... | |
virtual void | SetAnchor (unsigned int _index, const math::Vector3 &_anchor)=0 |
Set the anchor point. More... | |
virtual void | SetAxis (unsigned int _index, const math::Vector3 &_axis)=0 |
Set the axis of rotation where axis is specified in local joint frame. More... | |
virtual void | SetDamping (unsigned int _index, double _damping)=0 |
Set the joint damping. More... | |
virtual void | SetEffortLimit (unsigned int _index, double _effort) |
Set the effort limit on a joint axis. More... | |
virtual void | SetForce (unsigned int _index, double _effort)=0 |
Set the force applied to this physics::Joint. More... | |
virtual bool | SetHighStop (unsigned int _index, const math::Angle &_angle) |
Set the high stop of an axis(index). More... | |
void | SetLowerLimit (unsigned int _index, math::Angle _limit) |
: set the joint upper limit (replaces SetLowStop and SetHighStop) More... | |
virtual bool | SetLowStop (unsigned int _index, const math::Angle &_angle) |
Set the low stop of an axis(index). More... | |
void | SetModel (ModelPtr _model) |
Set the model this joint belongs too. More... | |
virtual void | SetName (const std::string &_name) |
Set the name of the entity. More... | |
virtual bool | SetParam (const std::string &_key, unsigned int _index, const boost::any &_value)=0 |
Set a non-generic parameter for the joint. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
virtual bool | SetPosition (unsigned int _index, double _position) |
The child links of this joint are updated based on desired position. More... | |
virtual void | SetProvideFeedback (bool _enable) |
Set whether the joint should generate feedback. More... | |
void | SetSaveable (bool _v) |
Set whether the object should be "saved", when the user selects to save the world to xml. More... | |
virtual bool | SetSelected (bool _show) |
Set whether this entity has been selected by the user through the gui. More... | |
void | SetState (const JointState &_state) |
Set the joint state. More... | |
virtual void | SetStiffness (unsigned int _index, double _stiffness)=0 |
Set the joint spring stiffness. More... | |
virtual void | SetStiffnessDamping (unsigned int _index, double _stiffness, double _damping, double _reference=0)=0 |
Set the joint spring stiffness. More... | |
void | SetStopDissipation (unsigned int _index, double _dissipation) |
Set joint stop dissipation. More... | |
void | SetStopStiffness (unsigned int _index, double _stiffness) |
Set joint stop stiffness. More... | |
void | SetUpperLimit (unsigned int _index, math::Angle _limit) |
: set the joint lower limit (replacee GetLowStop and GetHighStop) More... | |
virtual void | SetVelocity (unsigned int _index, double _vel)=0 |
Set the velocity of an axis(index). More... | |
virtual void | SetVelocityLimit (unsigned int _index, double _velocity) |
Set the velocity limit on a joint axis. More... | |
void | SetWorld (const WorldPtr &_newWorld) |
Set the world this object belongs to. More... | |
void | Update () |
Update the joint. More... | |
virtual void | UpdateParameters (sdf::ElementPtr _sdf) |
Update the parameters using new sdf values. More... | |
Protected Member Functions | |
math::Pose | ComputeChildLinkPose (unsigned int _index, double _position) |
internal function to help us compute child link pose if a joint position change is applied. More... | |
void | ComputeScopedName () |
Compute the scoped name of this object based on its parents. More... | |
bool | FindAllConnectedLinks (const LinkPtr &_originalParentLink, Link_V &_connectedLinks) |
internal helper to find all links connected to the child link branching out from the children of the child link and any parent of the child link other than the parent link through this joint. More... | |
virtual math::Angle | GetAngleImpl (unsigned int _index) const =0 |
Get the angle of an axis helper function. More... | |
bool | SetPositionMaximal (unsigned int _index, double _position) |
Helper function for maximal coordinate solver SetPosition. More... | |
bool | SetVelocityMaximal (unsigned int _index, double _velocity) |
Helper function for maximal coordinate solver SetVelocity. More... | |
Protected Attributes | |
LinkPtr | anchorLink |
Anchor link. More... | |
math::Vector3 | anchorPos |
Anchor pose. More... | |
math::Pose | anchorPose |
Anchor pose specified in SDF <joint><pose> tag. More... | |
gazebo::event::ConnectionPtr | applyDamping |
apply damping for adding viscous damping forces on updates More... | |
bool | axisParentModelFrame [2] |
Flags that are set to true if an axis value is expressed in the parent model frame. More... | |
LinkPtr | childLink |
The first link this joint connects to. More... | |
Base_V | children |
Children of this entity. More... | |
double | dissipationCoefficient [2] |
joint viscous damping coefficient More... | |
double | effortLimit [2] |
Store Joint effort limit as specified in SDF. More... | |
math::Angle | lowerLimit [2] |
Store Joint position lower limit as specified in SDF. More... | |
ModelPtr | model |
Pointer to the parent model. More... | |
BasePtr | parent |
Parent of this entity. More... | |
math::Pose | parentAnchorPose |
Anchor pose relative to parent link frame. More... | |
LinkPtr | parentLink |
The second link this joint connects to. More... | |
bool | provideFeedback |
Provide Feedback data for contact forces. More... | |
sdf::ElementPtr | sdf |
The SDF values for this object. More... | |
double | springReferencePosition [2] |
joint spring reference (zero load) position More... | |
double | stiffnessCoefficient [2] |
joint stiffnessCoefficient More... | |
math::Angle | upperLimit [2] |
Store Joint position upper limit as specified in SDF. More... | |
double | velocityLimit [2] |
Store Joint velocity limit as specified in SDF. More... | |
WorldPtr | world |
Pointer to the world. More... | |
JointWrench | wrench |
Cache Joint force torque values in case physics engine clears them at the end of update step. More... | |
Base class for all joints.
enum Attribute |
Joint attribute types.
|
inherited |
Unique identifiers for all entity types.
Enumerator | |
---|---|
BASE | Base type. |
ENTITY | Entity type. |
MODEL | Model type. |
LINK | Link type. |
COLLISION | Collision type. |
ACTOR | Actor type. |
LIGHT | Light type. |
VISUAL | Visual type. |
JOINT | Joint type. |
BALL_JOINT | BallJoint type. |
HINGE2_JOINT | Hing2Joint type. |
HINGE_JOINT | HingeJoint type. |
SLIDER_JOINT | SliderJoint type. |
SCREW_JOINT | ScrewJoint type. |
UNIVERSAL_JOINT | UniversalJoint type. |
GEARBOX_JOINT | GearboxJoint type. |
FIXED_JOINT | FixedJoint type. |
SHAPE | Shape type. |
BOX_SHAPE | BoxShape type. |
CYLINDER_SHAPE | CylinderShape type. |
HEIGHTMAP_SHAPE | HeightmapShape type. |
MAP_SHAPE | MapShape type. |
MULTIRAY_SHAPE | MultiRayShape type. |
RAY_SHAPE | RayShape type. |
PLANE_SHAPE | PlaneShape type. |
SPHERE_SHAPE | SphereShape type. |
MESH_SHAPE | MeshShape type. |
POLYLINE_SHAPE | PolylineShape type. |
SENSOR_COLLISION | Indicates a collision shape used for sensing. |
|
virtual |
Destructor.
|
inherited |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
Referenced by Base::Update().
|
virtual |
Callback to apply spring stiffness and viscous damping effects to joint.
: rename to ApplySpringStiffnessDamping()
Reimplemented in ODEJoint, and BulletJoint.
Determines of the two bodies are connected by a joint.
[in] | _one | First link. |
[in] | _two | Second link. |
Implemented in ODEJoint, BulletJoint, DARTJoint, and SimbodyJoint.
Attach the two bodies with this joint.
[in] | _parent | Parent link. |
[in] | _child | Child link. |
Reimplemented in ODEJoint, ODEFixedJoint, and DARTJoint.
|
virtual |
Cache Joint Force Torque Values if necessary for physics engine.
Reimplemented in SimbodyJoint, BulletJoint, ODEJoint, and DARTJoint.
Referenced by Joint::DisconnectJointUpdate().
double CheckAndTruncateForce | ( | unsigned int | _index, |
double | _effort | ||
) |
check if the force against velocityLimit and effortLimit, truncate if necessary.
[in] | _index | Index of the axis. |
[in] | _effort | Force value. |
Referenced by Joint::DisconnectJointUpdate().
|
protected |
internal function to help us compute child link pose if a joint position change is applied.
[in] | _index | axis index |
[in] | _position | new joint position |
Referenced by Joint::DisconnectJointUpdate().
|
protectedinherited |
Compute the scoped name of this object based on its parents.
Referenced by Base::Update().
|
inline |
Connect a boost::slot the the joint update signal.
[in] | _subscriber | Callback for the connection. |
References EventT< T >::Connect().
|
virtual |
Detach this joint from all links.
Reimplemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
|
inline |
Disconnect a boost::slot the the joint update signal.
[in] | _conn | Connection to disconnect. |
References Joint::CacheForceTorque(), Joint::CheckAndTruncateForce(), Joint::ComputeChildLinkPose(), EventT< T >::Disconnect(), Joint::FillMsg(), Joint::FindAllConnectedLinks(), Joint::GetAnchor(), Joint::GetAnchorErrorPose(), Joint::GetAngle(), Joint::GetAngleCount(), Joint::GetAngleImpl(), Joint::GetAxisFrame(), Joint::GetAxisFrameOffset(), Joint::GetChild(), Joint::GetEffortLimit(), Joint::GetForce(), Joint::GetForceTorque(), Joint::GetGlobalAxis(), Joint::GetHighStop(), Joint::GetInertiaRatio(), Joint::GetInitialAnchorPose(), Joint::GetLinkForce(), Joint::GetLinkTorque(), Joint::GetLocalAxis(), Joint::GetLowerLimit(), Joint::GetLowStop(), Joint::GetMsgType(), Joint::GetParam(), Joint::GetParent(), Joint::GetParentWorldPose(), Joint::GetStopDissipation(), Joint::GetStopStiffness(), Joint::GetUpperLimit(), Joint::GetVelocity(), Joint::GetVelocityLimit(), Joint::GetWorldEnergyPotentialSpring(), Joint::GetWorldPose(), Joint::SetAnchor(), Joint::SetEffortLimit(), Joint::SetForce(), Joint::SetHighStop(), Joint::SetLowerLimit(), Joint::SetLowStop(), Joint::SetParam(), Joint::SetPosition(), Joint::SetPositionMaximal(), Joint::SetProvideFeedback(), Joint::SetStopDissipation(), Joint::SetStopStiffness(), Joint::SetUpperLimit(), Joint::SetVelocity(), Joint::SetVelocityLimit(), and Joint::SetVelocityMaximal().
|
virtual |
Fill a joint message.
[out] | _msg | Message to fill with this joint's properties. |
Reimplemented in GearboxJoint< ODEJoint >, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, and ScrewJoint< BulletJoint >.
Referenced by Joint::DisconnectJointUpdate(), ScrewJoint< BulletJoint >::FillMsg(), and GearboxJoint< ODEJoint >::FillMsg().
|
protected |
internal helper to find all links connected to the child link branching out from the children of the child link and any parent of the child link other than the parent link through this joint.
[in] | _originalParentLink | parent link of this joint, this is used to check for loops connecting back to the parent link. |
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
|
pure virtual |
Get the anchor point.
[in] | _index | Index of the axis. |
Implemented in BulletJoint, SimbodyJoint, ODEHinge2Joint, BulletHinge2Joint, BulletScrewJoint, BulletBallJoint, BulletHingeJoint, BulletUniversalJoint, ODEGearboxJoint, ODEHingeJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, ODESliderJoint, SimbodyHinge2Joint, SimbodyUniversalJoint, DARTUniversalJoint, ODEFixedJoint, DARTBallJoint, DARTSliderJoint, DARTScrewJoint, ODEBallJoint, ODEUniversalJoint, ODEScrewJoint, and SimbodyBallJoint.
Referenced by Joint::DisconnectJointUpdate().
math::Pose GetAnchorErrorPose | ( | ) | const |
Get pose offset between anchor pose on child and parent, expressed in the parent link frame.
This can be used to compute the bilateral constraint error.
Referenced by Joint::DisconnectJointUpdate().
math::Angle GetAngle | ( | unsigned int | _index | ) | const |
Get the angle of rotation of an axis(index)
[in] | _index | Index of the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the angle count.
Implemented in DARTJoint, UniversalJoint< ODEJoint >, UniversalJoint< DARTJoint >, UniversalJoint< SimbodyJoint >, UniversalJoint< BulletJoint >, BallJoint< ODEJoint >, BallJoint< DARTJoint >, BallJoint< SimbodyJoint >, BallJoint< BulletJoint >, GearboxJoint< ODEJoint >, SliderJoint< ODEJoint >, SliderJoint< DARTJoint >, SliderJoint< SimbodyJoint >, SliderJoint< BulletJoint >, Hinge2Joint< ODEJoint >, Hinge2Joint< DARTJoint >, Hinge2Joint< SimbodyJoint >, Hinge2Joint< BulletJoint >, HingeJoint< ODEJoint >, HingeJoint< DARTJoint >, HingeJoint< SimbodyJoint >, HingeJoint< BulletJoint >, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, ScrewJoint< BulletJoint >, FixedJoint< ODEJoint >, FixedJoint< DARTJoint >, FixedJoint< SimbodyJoint >, and FixedJoint< BulletJoint >.
Referenced by Joint::DisconnectJointUpdate().
|
protectedpure virtual |
Get the angle of an axis helper function.
[in] | _index | Index of the axis. |
Implemented in BulletScrewJoint, BulletHinge2Joint, SimbodyScrewJoint, BulletSliderJoint, BulletHingeJoint, BulletUniversalJoint, DARTScrewJoint, BulletBallJoint, BulletFixedJoint, ODEScrewJoint, ODEGearboxJoint, SimbodyHinge2Joint, SimbodyUniversalJoint, SimbodyHingeJoint, ODEHinge2Joint, ODEHingeJoint, ODESliderJoint, SimbodyFixedJoint, ODEBallJoint, ODEFixedJoint, SimbodySliderJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, ODEUniversalJoint, DARTBallJoint, DARTUniversalJoint, SimbodyBallJoint, and DARTSliderJoint.
Referenced by Joint::DisconnectJointUpdate().
math::Quaternion GetAxisFrame | ( | unsigned int | _index | ) | const |
Get orientation of reference frame for specified axis, relative to world frame.
The value of axisParentModelFrame is used to determine the appropriate frame.
[in] | _index | joint axis index. |
Referenced by Joint::DisconnectJointUpdate().
math::Quaternion GetAxisFrameOffset | ( | unsigned int | _index | ) | const |
Get orientation of joint axis reference frame relative to joint frame.
This should always return identity unless flag use_parent_model_frame is true in sdf 1.5 or using sdf 1.4-, i.e. bug described in issue #494 is present. In addition, if use_parent_model_frame is true, and the parent link of the joint is world, the axis is defined in the world frame. The value of axisParentModelFrame is used to determine the appropriate frame internally.
[in] | _index | joint axis index. |
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
Referenced by Base::Update().
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
Referenced by Base::Update().
|
inherited |
Get a child by name.
[in] | _name | Name of the child. |
LinkPtr GetChild | ( | ) | const |
|
inherited |
double GetDamping | ( | unsigned int | _index | ) |
Returns the current joint damping coefficient.
[in] | _index | Index of the axis to get, currently ignored, to be implemented. |
|
virtual |
Get the effort limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Get external forces applied at this Joint. Note that the unit of force should be consistent with the rest of the simulation scales.
[in] | _index | Index of the axis. |
Reimplemented in ODEJoint, BulletJoint, DARTJoint, and SimbodyJoint.
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
get internal force and torque values at a joint.
The force and torque values are returned in a JointWrench data structure. Where JointWrench.body1Force contains the force applied by the parent Link on the Joint specified in the parent Link frame, and JointWrench.body2Force contains the force applied by the child Link on the Joint specified in the child Link frame. Note that this sign convention is opposite of the reaction forces of the Joint on the Links.
FIXME TODO: change name of this function to something like: GetNegatedForceTorqueInLinkFrame and make GetForceTorque call return non-negated reaction forces in perspective Link frames.
Note that for ODE you must set <provide_feedback>true<provide_feedback> in the joint sdf to use this.
[in] | _index | Not used right now |
Implemented in ODEJoint, BulletJoint, DARTJoint, and SimbodyJoint.
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the axis of rotation in global cooridnate frame.
[in] | _index | Index of the axis to get. |
Implemented in BulletScrewJoint, BulletHinge2Joint, SimbodyScrewJoint, BulletSliderJoint, BulletHingeJoint, BulletUniversalJoint, BulletBallJoint, BulletFixedJoint, SimbodyHinge2Joint, SimbodyUniversalJoint, ODEHinge2Joint, SimbodyBallJoint, SimbodyFixedJoint, ODEGearboxJoint, ODEHingeJoint, SimbodyHingeJoint, SimbodySliderJoint, DARTScrewJoint, ODESliderJoint, ODEFixedJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, ODEBallJoint, ODEUniversalJoint, ODEScrewJoint, DARTUniversalJoint, DARTBallJoint, and DARTSliderJoint.
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the high stop of an axis(index).
This function is replaced by GetUpperLimit(unsigned int). If you are interested in getting the value of dParamHiStop*, use GetAttribute(hi_stop, _index)
[in] | _index | Index of the axis. |
Implemented in ODEJoint, SimbodyJoint, BulletJoint, DARTJoint, DARTScrewJoint, BulletBallJoint, BulletHinge2Joint, BulletHingeJoint, BulletUniversalJoint, DARTBallJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
double GetInertiaRatio | ( | const unsigned int | _index | ) | const |
Computes moment of inertia (MOI) across a specified joint axis.
The ratio is given in the form of MOI_chidl / MOI_parent. If MOI_parent is zero, this funciton will return 0. The inertia ratio for each joint axis indicates the sensitivity of the joint to actuation torques.
[in] | _index | axis number about which MOI ratio is computed. |
Referenced by Joint::DisconnectJointUpdate().
double GetInertiaRatio | ( | const math::Vector3 & | _axis | ) | const |
Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame.
The ratio is given in the form of MOI_chidl / MOI_parent. If MOI_parent is zero, this funciton will return 0. The moment of inertia ratio along constrained directions of a joint has an impact on the performance of Projected Gauss Seidel (PGS) iterative LCP methods.
[in] | _axis | axis in world frame for which MOI ratio is computed. |
math::Pose GetInitialAnchorPose | ( | ) | const |
Get initial Anchor Pose specified by model <joint><pose>...</pose></joint>
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the link to which the joint is attached according the _index.
[in] | _index | Index of the link to retreive. |
Implemented in ODEJoint, BulletJoint, DARTJoint, and SimbodyJoint.
|
pure virtual |
Get the forces applied to the center of mass of a physics::Link due to the existence of this Joint.
Note that the unit of force should be consistent with the rest of the simulation scales.
[in] | index | The index of the link(0 or 1). |
Implemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the torque applied to the center of mass of a physics::Link due to the existence of this Joint.
Note that the unit of torque should be consistent with the rest of the simulation scales.
[in] | index | The index of the link(0 or 1) |
Implemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
Referenced by Joint::DisconnectJointUpdate().
math::Vector3 GetLocalAxis | ( | unsigned int | _index | ) | const |
Get the axis of rotation.
[in] | _index | Index of the axis to get. |
Referenced by Joint::DisconnectJointUpdate().
math::Angle GetLowerLimit | ( | unsigned int | _index | ) | const |
: get the joint upper limit (replaces GetLowStop and GetHighStop)
[in] | _index | Index of the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the low stop of an axis(index).
This function is replaced by GetLowerLimit(unsigned int). If you are interested in getting the value of dParamHiStop*, use GetAttribute(hi_stop, _index)
[in] | _index | Index of the axis. |
Implemented in ODEJoint, SimbodyJoint, BulletJoint, DARTJoint, DARTScrewJoint, BulletBallJoint, BulletHinge2Joint, BulletHingeJoint, BulletUniversalJoint, DARTBallJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
msgs::Joint::Type GetMsgType | ( | ) | const |
Get the joint type as msgs::Joint::Type.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
|
virtual |
Get a non-generic parameter for the joint.
[in] | _key | String key. |
[in] | _index | Index of the axis. |
Reimplemented in ODEJoint, DARTJoint, BulletScrewJoint, BulletJoint, SimbodyScrewJoint, ODEScrewJoint, BulletSliderJoint, BulletHingeJoint, BulletUniversalJoint, SimbodyJoint, ODEUniversalJoint, and DARTScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
LinkPtr GetParent | ( | ) | const |
Get the parent link.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
math::Pose GetParentWorldPose | ( | ) | const |
Get anchor pose on parent link relative to world frame.
When there is zero joint error, this should match the value returned by Joint::GetWorldPose() for the constrained degrees of freedom.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
Referenced by Base::Update().
|
inherited |
Return the name of this entity with the model scope model1::...::modelN::entityName.
[in] | _prependWorldName | True to prended the returned string with the world name. The result will be world::model1::...::modelN::entityName. |
Referenced by Base::Update().
|
virtualinherited |
Get the SDF values for the object.
Reimplemented in Actor, and Model.
Referenced by Base::Update().
double GetSpringReferencePosition | ( | unsigned int | _index | ) | const |
Get joint spring reference position.
[in] | _index | Index of the axis to get. |
double GetStiffness | ( | unsigned int | _index | ) |
Returns the current joint spring stiffness coefficient.
[in] | _index | Index of the axis to get, currently ignored, to be implemented. |
double GetStopDissipation | ( | unsigned int | _index | ) | const |
Get joint stop dissipation.
[in] | _index | joint axis index. |
Referenced by Joint::DisconnectJointUpdate().
double GetStopStiffness | ( | unsigned int | _index | ) | const |
Get joint stop stiffness.
[in] | _index | joint axis index. |
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
math::Angle GetUpperLimit | ( | unsigned int | _index | ) | const |
: get the joint lower limit (replacee GetLowStop and GetHighStop)
[in] | _index | Index of the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Get the rotation rate of an axis(index)
[in] | _index | Index of the axis. |
Implemented in BulletScrewJoint, DARTScrewJoint, SimbodyScrewJoint, ODEGearboxJoint, ODEScrewJoint, BulletSliderJoint, ODEHingeJoint, BulletHinge2Joint, ODEHinge2Joint, ODEFixedJoint, DARTFixedJoint, DARTHingeJoint, ODESliderJoint, BulletBallJoint, DARTHinge2Joint, DARTSliderJoint, ODEUniversalJoint, BulletHingeJoint, SimbodyUniversalJoint, BulletUniversalJoint, DARTUniversalJoint, BulletFixedJoint, ODEBallJoint, SimbodyHinge2Joint, DARTBallJoint, SimbodyBallJoint, SimbodyHingeJoint, SimbodySliderJoint, and SimbodyFixedJoint.
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Get the velocity limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Get the World this object is in.
Referenced by Base::Update().
double GetWorldEnergyPotentialSpring | ( | unsigned int | _index | ) | const |
Returns this joint's spring potential energy, based on the reference position of the spring.
If using metric system, the unit of energy will be Joules.
Referenced by Joint::DisconnectJointUpdate().
math::Pose GetWorldPose | ( | ) | const |
Get pose of joint frame relative to world frame.
Note that the joint frame is defined with a fixed offset from the child link frame.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
Referenced by Base::Update().
|
virtual |
Initialize a joint.
Reimplemented from Base.
Reimplemented in BulletJoint, GearboxJoint< ODEJoint >, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, ScrewJoint< BulletJoint >, UniversalJoint< ODEJoint >, UniversalJoint< DARTJoint >, UniversalJoint< SimbodyJoint >, UniversalJoint< BulletJoint >, BallJoint< ODEJoint >, BallJoint< DARTJoint >, BallJoint< SimbodyJoint >, BallJoint< BulletJoint >, BulletScrewJoint, HingeJoint< ODEJoint >, HingeJoint< DARTJoint >, HingeJoint< SimbodyJoint >, HingeJoint< BulletJoint >, BulletHinge2Joint, DARTScrewJoint, FixedJoint< ODEJoint >, FixedJoint< DARTJoint >, FixedJoint< SimbodyJoint >, FixedJoint< BulletJoint >, DARTJoint, BulletBallJoint, BulletFixedJoint, BulletHingeJoint, BulletSliderJoint, BulletUniversalJoint, ODEGearboxJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, DARTUniversalJoint, DARTBallJoint, and DARTSliderJoint.
|
inherited |
True if the entity is selected by the user.
Referenced by Base::Update().
void Load | ( | LinkPtr | _parent, |
LinkPtr | _child, | ||
const math::Pose & | _pose | ||
) |
Set pose, parent and child links of a physics::Joint.
[in] | _parent | Parent link. |
[in] | _child | Child link. |
[in] | _pose | Pose containing Joint Anchor offset from child link. |
|
virtual |
Load physics::Joint from a SDF sdf::Element.
[in] | _sdf | SDF values to load from. |
Reimplemented from Base.
Reimplemented in SimbodySliderJoint, BallJoint< ODEJoint >, BallJoint< DARTJoint >, BallJoint< SimbodyJoint >, BallJoint< BulletJoint >, UniversalJoint< ODEJoint >, UniversalJoint< DARTJoint >, UniversalJoint< SimbodyJoint >, UniversalJoint< BulletJoint >, GearboxJoint< ODEJoint >, Hinge2Joint< ODEJoint >, Hinge2Joint< DARTJoint >, Hinge2Joint< SimbodyJoint >, Hinge2Joint< BulletJoint >, ODEJoint, HingeJoint< ODEJoint >, HingeJoint< DARTJoint >, HingeJoint< SimbodyJoint >, HingeJoint< BulletJoint >, BulletScrewJoint, BulletHinge2Joint, ScrewJoint< ODEJoint >, ScrewJoint< DARTJoint >, ScrewJoint< SimbodyJoint >, ScrewJoint< BulletJoint >, DARTJoint, ODEHinge2Joint, ODEHingeJoint, SliderJoint< ODEJoint >, SliderJoint< DARTJoint >, SliderJoint< SimbodyJoint >, SliderJoint< BulletJoint >, BulletBallJoint, BulletJoint, SimbodyFixedJoint, FixedJoint< ODEJoint >, FixedJoint< DARTJoint >, FixedJoint< SimbodyJoint >, FixedJoint< BulletJoint >, BulletFixedJoint, BulletHingeJoint, BulletSliderJoint, BulletUniversalJoint, ODEGearboxJoint, ODESliderJoint, SimbodyHinge2Joint, SimbodyHingeJoint, SimbodyUniversalJoint, ODEFixedJoint, SimbodyScrewJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, SimbodyJoint, DARTScrewJoint, DARTUniversalJoint, ODEScrewJoint, SimbodyBallJoint, DARTBallJoint, and DARTSliderJoint.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
Referenced by Base::Update().
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
Referenced by Base::Update().
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
Referenced by Base::Update().
|
inherited |
Remove a child by name.
[in] | _name | Name of the child. |
|
inherited |
Remove a child by pointer.
[in] | _child | Pointer to the child. |
|
inherited |
Remove all children.
Referenced by Base::Update().
|
virtual |
Reset the joint.
Reimplemented from Base.
Reimplemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
pure virtual |
Set the anchor point.
[in] | _index | Indx of the axis. |
[in] | _anchor | Anchor value. |
Implemented in DARTJoint, BulletJoint, SimbodyJoint, BulletScrewJoint, ODEGearboxJoint, ODEHingeJoint, ODEHinge2Joint, ODESliderJoint, ODEFixedJoint, DARTScrewJoint, ODEBallJoint, ODEUniversalJoint, and ODEScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Set the axis of rotation where axis is specified in local joint frame.
[in] | _index | Index of the axis to set. |
[in] | _axis | Vector in local joint frame of axis direction (must have length greater than zero). |
Implemented in ODEJoint, SimbodyJoint, BulletBallJoint, BulletScrewJoint, DARTBallJoint, ODEBallJoint, SimbodyBallJoint, ODEGearboxJoint, ODEHingeJoint, BulletHinge2Joint, DARTScrewJoint, ODESliderJoint, ODEFixedJoint, DARTFixedJoint, DARTHinge2Joint, DARTHingeJoint, ODEHinge2Joint, ODEUniversalJoint, BulletHingeJoint, BulletUniversalJoint, ODEScrewJoint, DARTUniversalJoint, DARTSliderJoint, BulletFixedJoint, BulletSliderJoint, SimbodyHinge2Joint, SimbodyUniversalJoint, SimbodyHingeJoint, SimbodyScrewJoint, and SimbodySliderJoint.
|
pure virtual |
Set the joint damping.
[in] | _index | Index of the axis to set, currently ignored, to be implemented. |
[in] | _damping | Damping value for the axis. |
Implemented in ODEJoint, DARTJoint, BulletJoint, SimbodyJoint, and BulletSliderJoint.
|
virtual |
Set the effort limit on a joint axis.
[in] | _index | Index of the axis to set. |
[in] | _effort | Effort limit for the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Set the force applied to this physics::Joint.
Note that the unit of force should be consistent with the rest of the simulation scales. Force is additive (multiple calls to SetForce to the same joint in the same time step will accumulate forces on that Joint). Forces are truncated by effortLimit before applied.
[in] | _index | Index of the axis. |
[in] | _effort | Force value. |
Implemented in ODEJoint, BulletJoint, DARTJoint, and SimbodyJoint.
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Set the high stop of an axis(index).
[in] | _index | Index of the axis. |
[in] | _angle | High stop angle. |
Reimplemented in ODEJoint, SimbodyJoint, DARTJoint, BulletScrewJoint, BulletHinge2Joint, DARTBallJoint, ODEBallJoint, SimbodyBallJoint, ODEUniversalJoint, BulletBallJoint, BulletHingeJoint, BulletUniversalJoint, BulletFixedJoint, BulletSliderJoint, and SimbodyScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
void SetLowerLimit | ( | unsigned int | _index, |
math::Angle | _limit | ||
) |
: set the joint upper limit (replaces SetLowStop and SetHighStop)
[in] | _index | Index of the axis. |
[in] | _limit | Lower limit of the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Set the low stop of an axis(index).
[in] | _index | Index of the axis. |
[in] | _angle | Low stop angle. |
Reimplemented in ODEJoint, SimbodyJoint, DARTJoint, BulletScrewJoint, BulletHinge2Joint, DARTBallJoint, ODEBallJoint, SimbodyBallJoint, ODEUniversalJoint, BulletBallJoint, BulletHingeJoint, BulletUniversalJoint, BulletFixedJoint, BulletSliderJoint, and SimbodyScrewJoint.
Referenced by Joint::DisconnectJointUpdate().
void SetModel | ( | ModelPtr | _model | ) |
Set the model this joint belongs too.
[in] | _model | Pointer to a model. |
|
virtualinherited |
Set the name of the entity.
[in] | _name | New name. |
Reimplemented in Entity.
Referenced by Base::Update().
|
pure virtual |
Set a non-generic parameter for the joint.
replaces SetAttribute(Attribute, int, double) List of parameters: "friction" Axis Coulomb joint friction coefficient. "hi_stop" Axis upper limit. "lo_stop" Axis lower limit.
[in] | _key | String key. |
[in] | _index | Index of the axis. |
[in] | _value | Value of the attribute. |
Implemented in ODEJoint, DARTJoint, BulletJoint, SimbodyScrewJoint, ODEScrewJoint, BulletSliderJoint, BulletHingeJoint, BulletUniversalJoint, SimbodyJoint, and ODEUniversalJoint.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
|
virtual |
The child links of this joint are updated based on desired position.
And all the links connected to the child link of this joint except through the parent link of this joint moves with the child link.
[in] | _index | Index of the joint axis (degree of freedom). |
[in] | _position | Position to set the joint to. unspecified, pure kinematic teleportation. |
Reimplemented in ODEJoint, and BulletJoint.
Referenced by Joint::DisconnectJointUpdate().
|
protected |
Helper function for maximal coordinate solver SetPosition.
The child links of this joint are updated based on position change. And all the links connected to the child link of this joint except through the parent link of this joint moves with the child link.
[in] | _index | Index of the joint axis (degree of freedom). |
[in] | _position | Position to set the joint to. |
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Set whether the joint should generate feedback.
[in] | _enable | True to enable joint feedback. |
Reimplemented in ODEJoint, and BulletJoint.
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Set whether the object should be "saved", when the user selects to save the world to xml.
[in] | _v | Set to True if the object should be saved. |
Referenced by Base::Update().
|
virtualinherited |
Set whether this entity has been selected by the user through the gui.
[in] | _show | True to set this entity as selected. |
Reimplemented in Link.
Referenced by Base::Update().
void SetState | ( | const JointState & | _state | ) |
Set the joint state.
[in] | _state | Joint state |
|
pure virtual |
Set the joint spring stiffness.
[in] | _index | Index of the axis to set, currently ignored, to be implemented. |
[in] | _stiffness | Spring stiffness value for the axis. : rename to SetSpringStiffness() |
Implemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
|
pure virtual |
Set the joint spring stiffness.
[in] | _index | Index of the axis to set, currently ignored, to be implemented. |
[in] | _stiffness | Stiffness value for the axis. |
[in] | _reference | Spring zero load reference position. : rename to SetSpringStiffnessDamping() |
Implemented in ODEJoint, DARTJoint, BulletJoint, and SimbodyJoint.
void SetStopDissipation | ( | unsigned int | _index, |
double | _dissipation | ||
) |
Set joint stop dissipation.
[in] | _index | joint axis index. |
[in] | _dissipation | joint stop dissipation coefficient. |
Referenced by Joint::DisconnectJointUpdate().
void SetStopStiffness | ( | unsigned int | _index, |
double | _stiffness | ||
) |
Set joint stop stiffness.
[in] | _index | joint axis index. |
[in] | _stiffness | joint stop stiffness coefficient. |
Referenced by Joint::DisconnectJointUpdate().
void SetUpperLimit | ( | unsigned int | _index, |
math::Angle | _limit | ||
) |
: set the joint lower limit (replacee GetLowStop and GetHighStop)
[in] | _index | Index of the axis. |
[in] | _limit | Upper limit of the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
pure virtual |
Set the velocity of an axis(index).
In ODE and Bullet, the SetVelocityMaximal function is used to set the velocity of the child link relative to the parent. In Simbody and DART, this function updates the velocity state, which has a recursive effect on the rest of the chain.
[in] | _index | Index of the axis. |
[in] | _vel | Velocity. |
Implemented in BulletScrewJoint, DARTScrewJoint, SimbodyScrewJoint, ODEScrewJoint, BulletSliderJoint, BulletHinge2Joint, ODEGearboxJoint, ODEHinge2Joint, ODEHingeJoint, ODESliderJoint, DARTHinge2Joint, ODEUniversalJoint, ODEFixedJoint, DARTUniversalJoint, DARTFixedJoint, DARTHingeJoint, SimbodyHinge2Joint, BulletBallJoint, DARTSliderJoint, BulletHingeJoint, SimbodyUniversalJoint, BulletUniversalJoint, BulletFixedJoint, ODEBallJoint, SimbodyFixedJoint, DARTBallJoint, SimbodyBallJoint, SimbodyHingeJoint, and SimbodySliderJoint.
Referenced by Joint::DisconnectJointUpdate().
|
virtual |
Set the velocity limit on a joint axis.
[in] | _index | Index of the axis to set. |
[in] | _velocity | Velocity limit for the axis. |
Referenced by Joint::DisconnectJointUpdate().
|
protected |
Helper function for maximal coordinate solver SetVelocity.
The velocity of the child link of this joint is updated relative to the current parent velocity. It currently does not act recursively.
[in] | _index | Index of the joint axis (degree of freedom). |
[in] | _velocity | Velocity to set at this joint. |
Referenced by Joint::DisconnectJointUpdate().
|
inherited |
Set the world this object belongs to.
This will also set the world for all children.
[in] | _newWorld | The new World this object is part of. |
Referenced by Base::Update().
|
virtual |
Update the joint.
Reimplemented from Base.
|
virtual |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to update from. |
Reimplemented from Base.
|
protected |
Anchor link.
|
protected |
Anchor pose.
This is the xyz offset of the joint frame from child frame specified in the parent link frame
|
protected |
Anchor pose specified in SDF <joint><pose> tag.
AnchorPose is the transform from child link frame to joint frame specified in the child link frame. AnchorPos is more relevant in normal usage, but sometimes, we do need this (e.g. GetForceTorque and joint visualization).
|
protected |
apply damping for adding viscous damping forces on updates
|
protected |
Flags that are set to true if an axis value is expressed in the parent model frame.
Otherwise use the joint frame. See issue #494.
|
protected |
The first link this joint connects to.
|
protectedinherited |
Children of this entity.
|
protected |
joint viscous damping coefficient
|
protected |
Store Joint effort limit as specified in SDF.
|
protected |
Store Joint position lower limit as specified in SDF.
|
protected |
Pointer to the parent model.
|
protectedinherited |
Parent of this entity.
|
protected |
Anchor pose relative to parent link frame.
|
protected |
The second link this joint connects to.
|
protected |
Provide Feedback data for contact forces.
|
protectedinherited |
The SDF values for this object.
|
protected |
joint spring reference (zero load) position
|
protected |
joint stiffnessCoefficient
|
protected |
Store Joint position upper limit as specified in SDF.
|
protected |
Store Joint velocity limit as specified in SDF.
|
protectedinherited |
Pointer to the world.
|
protected |
Cache Joint force torque values in case physics engine clears them at the end of update step.