A screw joint. More...
#include <BulletScrewJoint.hh>
Inherits ScrewJoint< BulletJoint >.
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, 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, ACTOR = 0x00008000, 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 | |
BulletScrewJoint (btDynamicsWorld *_world, BasePtr _parent) | |
Constructor. More... | |
virtual | ~BulletScrewJoint () |
Destructor. More... | |
void | AddChild (BasePtr _child) |
Add a child to this entity. More... | |
void | AddType (EntityType _type) |
Add a type specifier. More... | |
virtual ignition::math::Vector3d | Anchor (const unsigned int _index) const |
Get the anchor point. More... | |
ignition::math::Pose3d | AnchorErrorPose () const |
Get pose offset between anchor pose on child and parent, expressed in the parent link frame. More... | |
virtual void | ApplyStiffnessDamping () |
Callback to apply spring stiffness and viscous damping effects to joint. More... | |
bool | AreConnected (LinkPtr _one, LinkPtr _two) const |
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... | |
ignition::math::Quaterniond | AxisFrame (const unsigned int _index) const |
Get orientation of reference frame for specified axis, relative to world frame. More... | |
ignition::math::Quaterniond | AxisFrameOffset (const unsigned int _index) const |
Get orientation of joint axis reference frame relative to joint frame. 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 bodies. More... | |
virtual unsigned int | DOF () const |
virtual void | FillMsg (msgs::Joint &_msg) |
virtual void | Fini () |
Finialize the object. 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) |
get internal force and torque values at a joint. 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... | |
LinkPtr | GetJointLink (unsigned int _index) const |
Get the body to which the joint is attached according the _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... | |
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... | |
virtual double | GetThreadPitch (unsigned int _index) |
virtual double | GetThreadPitch () |
Get screw joint thread pitch. More... | |
unsigned int | GetType () const |
Get the full type definition. More... | |
virtual double | GetVelocity (unsigned int _index) const |
Get the rate of change. 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... | |
virtual ignition::math::Vector3d | GlobalAxis (const unsigned int _index) const |
Get the axis of rotation. More... | |
bool | HasType (const EntityType &_t) const |
Returns true if this object's type definition has the given type. More... | |
double | InertiaRatio (const ignition::math::Vector3d &_axis) const |
Computes moment of inertia (MOI) across an arbitrary axis specified in the world frame. More... | |
virtual void | Init () |
Initialize joint. More... | |
ignition::math::Pose3d | InitialAnchorPose () const |
Get initial Anchor Pose specified by model <joint><pose>...</pose></joint> More... | |
bool | IsSelected () const |
True if the entity is selected by the user. More... | |
virtual ignition::math::Vector3d | LinkForce (const unsigned int _index) const |
Get the force the joint applies to the first body. More... | |
virtual ignition::math::Vector3d | LinkTorque (const unsigned int _index) const |
Get the torque the joint applies to the first body. More... | |
virtual void | Load (sdf::ElementPtr _sdf) |
Load the BulletScrewJoint. More... | |
void | Load (LinkPtr _parent, LinkPtr _child, const ignition::math::Pose3d &_pose) |
Set pose, parent and child links of a physics::Joint. More... | |
ignition::math::Vector3d | LocalAxis (const unsigned int _index) const |
Get the axis of rotation. More... | |
virtual double | LowerLimit (unsigned int _index=0) const |
Get the joint's lower limit. More... | |
bool | operator== (const Base &_ent) const |
Returns true if the entities are the same. More... | |
ignition::math::Pose3d | ParentWorldPose () const |
Get anchor pose on parent link relative to world frame. More... | |
virtual double | Position (const unsigned int _index=0) const final |
Get the position of an axis according to its index. 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 (const unsigned int _index, const ignition::math::Vector3d &_anchor) |
Set the anchor point. More... | |
void | SetAxis (const unsigned int _index, const ignition::math::Vector3d &_axis) |
Set the axis of motion. More... | |
virtual void | SetDamping (unsigned int _index, double _damping) |
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 _force) |
Set the force applied to this physics::Joint. More... | |
virtual void | SetLowerLimit (const unsigned int _index, const double _limit) |
Set the joint's lower limit. 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) |
Set a non-generic parameter for the joint. More... | |
void | SetParent (BasePtr _parent) |
Set the parent. More... | |
virtual bool | SetPosition (const unsigned int _index, const double _position, const bool _preserveWorldVelocity=false) override |
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, const double _stiffness) |
Set the joint spring stiffness. More... | |
virtual void | SetStiffnessDamping (unsigned int _index, double _stiffness, double _damping, double _reference=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... | |
virtual void | SetThreadPitch (unsigned int _index, double _threadPitch) |
virtual void | SetThreadPitch (double _threadPitch) |
Set screw joint thread pitch. More... | |
virtual void | SetUpperLimit (const unsigned int _index, const double _limit) |
Set the joint's upper limit. More... | |
virtual void | SetVelocity (unsigned int _index, double _vel) |
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... | |
std::string | TypeStr () const |
Get the string name for the entity type. More... | |
void | Update () |
Update the joint. More... | |
virtual void | UpdateParameters (sdf::ElementPtr _sdf) |
Update the parameters using new sdf values. More... | |
virtual double | UpperLimit (const unsigned int _index=0) const |
Get the joint's upper limit. More... | |
common::URI | URI () const |
Return the common::URI of this entity. More... | |
ignition::math::Pose3d | WorldPose () const |
Get pose of joint frame relative to world frame. More... | |
Protected Member Functions | |
ignition::math::Pose3d | ChildLinkPose (const unsigned int _index, const 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 double | PositionImpl (const unsigned int _index) const |
Helper function to get the position of an axis. More... | |
virtual void | RegisterIntrospectionItems () |
Register items in the introspection service. More... | |
virtual void | SetForceImpl (unsigned int _index, double _force) |
Set the force applied to this physics::Joint. More... | |
bool | SetPositionMaximal (const unsigned int _index, double _position, const bool _preserveWorldVelocity=false) |
Helper function for maximal coordinate solver SetPosition. More... | |
void | SetupJointFeedback () |
: Setup joint feedback datatructure. More... | |
bool | SetVelocityMaximal (unsigned int _index, double _velocity) |
Helper function for maximal coordinate solver SetVelocity. More... | |
virtual void | UnregisterIntrospectionItems () |
Unregister items in the introspection service. More... | |
Protected Attributes | |
LinkPtr | anchorLink |
Anchor link. More... | |
ignition::math::Vector3d | anchorPos |
Anchor pose. More... | |
ignition::math::Pose3d | 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... | |
btDynamicsWorld * | bulletWorld |
Pointer to Bullet's btDynamicsWorld. More... | |
LinkPtr | childLink |
The first link this joint connects to. More... | |
Base_V | children |
Children of this entity. More... | |
btTypedConstraint * | constraint |
Pointer to a contraint object in Bullet. More... | |
double | dissipationCoefficient [2] |
joint viscous damping coefficient More... | |
double | effortLimit [2] |
Store Joint effort limit as specified in SDF. More... | |
std::vector< common::URI > | introspectionItems |
All the introspection items regsitered for this. More... | |
double | 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... | |
ignition::math::Pose3d | 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... | |
double | threadPitch |
Pitch of the thread. More... | |
double | 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... | |
A screw joint.
|
inherited |
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. |
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. |
ACTOR |
Actor 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. |
BulletScrewJoint | ( | btDynamicsWorld * | _world, |
BasePtr | _parent | ||
) |
Constructor.
[in] | _world | Pointer to the dynamics world. |
[in] | _parent | Pointer to the parent. |
|
virtual |
Destructor.
|
inherited |
Add a child to this entity.
[in] | _child | Child entity. |
|
inherited |
Add a type specifier.
[in] | _type | New type to append to this objects type definition. |
|
virtual |
Get the anchor point.
Reimplemented from BulletJoint.
|
inherited |
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.
|
virtualinherited |
Callback to apply spring stiffness and viscous damping effects to joint.
: rename to ApplySpringStiffnessDamping()
Reimplemented from Joint.
Determines of the two bodies are connected by a joint.
Implements Joint.
Attach the two bodies with this joint.
[in] | _parent | Parent link. |
[in] | _child | Child link. |
Reimplemented in ODEJoint, ODEFixedJoint, and DARTJoint.
|
inherited |
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. |
|
inherited |
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. |
|
virtualinherited |
|
inherited |
check if the force against velocityLimit and effortLimit, truncate if necessary.
[in] | _index | Index of the axis. |
[in] | _effort | Force value. |
|
protectedinherited |
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 |
|
protectedinherited |
Compute the scoped name of this object based on its parents.
|
inlineinherited |
Connect a boost::slot the the joint update signal.
[in] | _subscriber | Callback for the connection. |
References EventT< T >::Connect().
|
virtualinherited |
Detach this joint from all bodies.
Reimplemented from Joint.
|
inlinevirtualinherited |
Implements Joint.
|
inlinevirtualinherited |
Reimplemented from Joint.
References Joint::FillMsg(), and ScrewJoint< T >::threadPitch.
|
protectedinherited |
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. |
in/out] | _connectedLinks list of aggregated links that contains all links connected to the child link of this joint. Empty if a loop is found that connects back to the parent link. |
|
virtualinherited |
Finialize the object.
Reimplemented from Joint.
|
inherited |
Get by name.
[in] | _name | Get a child (or self) object by name |
|
inherited |
Get a child by index.
[in] | _i | Index of the child to retreive. |
|
inherited |
Get a child by name.
[in] | _name | Name of the child. |
|
inherited |
Get the child link.
|
inherited |
Get the number of children.
|
inherited |
Returns the current joint damping coefficient.
[in] | _index | Index of the axis to get, currently ignored, to be implemented. |
|
virtualinherited |
Get the effort limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
|
virtualinherited |
|
virtualinherited |
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 |
Implements Joint.
|
inherited |
Return the ID of this entity.
This id is unique.
|
inherited |
Computes moment of inertia (MOI) across a specified joint axis.
The ratio is given in the form of MOI_child / 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. |
|
virtualinherited |
Get the body to which the joint is attached according the _index.
Implements Joint.
|
inherited |
Get the joint type as msgs::Joint::Type.
|
inherited |
Return the name of the entity.
|
virtual |
Get a non-generic parameter for the joint.
[in] | _key | String key. |
[in] | _index | Index of the axis. |
Reimplemented from BulletJoint.
|
inherited |
Get the parent link.
|
inherited |
Return the ID of the parent.
|
inherited |
Get whether the object should be "saved", when the user selects to save the world to xml.
|
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. |
|
virtualinherited |
|
inherited |
Get joint spring reference position.
[in] | _index | Index of the axis to get. |
|
inherited |
Returns the current joint spring stiffness coefficient.
[in] | _index | Index of the axis to get, currently ignored, to be implemented. |
|
inherited |
Get joint stop dissipation.
[in] | _index | joint axis index. |
|
inherited |
Get joint stop stiffness.
[in] | _index | joint axis index. |
|
virtual |
|
virtual |
Get screw joint thread pitch.
Thread Pitch is defined as angular motion per linear motion or rad / m in metric. This must be implemented in a child class
Implements ScrewJoint< BulletJoint >.
|
inherited |
Get the full type definition.
|
virtual |
|
virtualinherited |
Get the velocity limit on axis(index).
[in] | _index | Index of axis, where 0=first axis and 1=second axis |
|
inherited |
|
inherited |
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.
|
virtual |
Get the axis of rotation.
[in] | _index | Axis index. |
Implements Joint.
|
inherited |
Returns true if this object's type definition has the given type.
[in] | _t | Type to check. |
|
inherited |
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. |
|
virtual |
Initialize joint.
Reimplemented from ScrewJoint< BulletJoint >.
|
inherited |
Get initial Anchor Pose specified by model <joint><pose>...</pose></joint>
|
inherited |
True if the entity is selected by the user.
|
virtualinherited |
Get the force the joint applies to the first body.
index | The index of the body(0 or 1) |
Implements Joint.
|
virtualinherited |
Get the torque the joint applies to the first body.
index | The index of the body(0 or 1) |
Implements Joint.
|
virtual |
Load the BulletScrewJoint.
[in] | _sdf | SDF values. |
Reimplemented from ScrewJoint< BulletJoint >.
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. |
|
inherited |
Get the axis of rotation.
[in] | _index | Index of the axis to get. |
|
virtualinherited |
Get the joint's lower limit.
For rotational axes, the value is in radians, for prismatic axes it is in meters.
[in] | _index | Index of the axis, defaults to 0. |
Reimplemented in SimbodyJoint, DARTJoint, BulletBallJoint, BulletHinge2Joint, BulletUniversalJoint, BulletHingeJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.
|
inherited |
Returns true if the entities are the same.
Checks only the name.
[in] | _ent | Base object to compare with. |
|
inherited |
Get anchor pose on parent link relative to world frame.
When there is zero joint error, this should match the value returned by Joint::WorldPose() for the constrained degrees of freedom.
|
finalvirtualinherited |
Get the position of an axis according to its index.
For rotational axes, the value is in radians. For prismatic axes, it is in meters.
For static models, it returns the static joint position.
It returns ignition::math::NAN_D in case the position can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.
Subclasses can't override this method. See PositionImpl instead.
[in] | _index | Index of the axis, defaults to 0. |
|
protectedvirtual |
|
inherited |
Print this object to screen via gzmsg.
[in] | _prefix | Usually a set of spaces. |
|
protectedvirtualinherited |
Register items in the introspection service.
Reimplemented from Base.
|
virtualinherited |
Remove a child from this entity.
[in] | _id | ID of the child to remove. |
|
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.
|
virtualinherited |
Reset the joint.
Reimplemented from Joint.
|
virtualinherited |
Calls recursive Reset on one of the Base::EntityType's.
[in] | _resetType | The type of reset operation |
|
virtual |
Set the anchor point.
Reimplemented from BulletJoint.
|
virtual |
|
virtualinherited |
Set the joint damping.
[in] | _index | Index of the axis to set, currently ignored, to be implemented. |
[in] | _damping | Damping value for the axis. |
Implements Joint.
Reimplemented in BulletSliderJoint.
|
virtualinherited |
Set the effort limit on a joint axis.
[in] | _index | Index of the axis to set. |
[in] | _effort | Effort limit for the axis. |
|
virtualinherited |
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. |
Implements Joint.
|
protectedvirtual |
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 SetForceImpl to the same joint in the same time step will accumulate forces on that Joint).
[in] | _index | Index of the axis. |
[in] | _force | Force value. internal force, e.g. damping forces. This way, Joint::appliedForce keep track of external forces only. |
Implements BulletJoint.
|
virtual |
Set the joint's lower limit.
For rotational axes, the value is in radians. For prismatic axes, it is in meters.
It returns ignition::math::NAN_D in case the limit can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.
[in] | _index | Index of the axis. |
[in] | _limit | Lower limit of the axis. |
Reimplemented from Joint.
|
inherited |
Set the model this joint belongs too.
[in] | _model | Pointer to a model. |
|
virtualinherited |
|
virtualinherited |
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. |
Implements Joint.
Reimplemented in BulletUniversalJoint, BulletHingeJoint, and BulletSliderJoint.
|
inherited |
Set the parent.
[in] | _parent | Parent object. |
|
overridevirtualinherited |
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. |
[in] | _preserveWorldVelocity | If true, the velocity of the child link with respect to the world frame will remain the same after setting the position. By default this is false, which means there are no guarantees about what the child link's world velocity will be after the position is changed (the behavior is determined by the underlying physics engine). |
Reimplemented from Joint.
|
protectedinherited |
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. |
[in] | _preserveWorldVelocity | True if to preserve the world velocity before set position, default is false. |
|
virtualinherited |
Set whether the joint should generate feedback.
[in] | _enable | True to enable joint feedback. |
Reimplemented from Joint.
|
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. |
|
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.
|
inherited |
Set the joint state.
[in] | _state | Joint state |
|
virtualinherited |
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() |
Implements Joint.
|
virtualinherited |
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() |
Implements Joint.
|
inherited |
Set joint stop dissipation.
[in] | _index | joint axis index. |
[in] | _dissipation | joint stop dissipation coefficient. |
|
inherited |
Set joint stop stiffness.
[in] | _index | joint axis index. |
[in] | _stiffness | joint stop stiffness coefficient. |
|
virtual |
|
virtual |
Set screw joint thread pitch.
Thread Pitch is defined as angular motion per linear motion or rad / m in metric. This must be implemented in a child class To clarify direction, these are modeling right handed threads with positive thread_pitch, i.e. the child Link is the nut (interior threads) while the parent Link is the bolt/screw (exterior threads).
[in] | _threadPitch | Thread pitch value. |
Implements ScrewJoint< BulletJoint >.
|
protectedinherited |
: Setup joint feedback datatructure.
This is called after Joint::constraint is setup in Init.
|
virtual |
Set the joint's upper limit.
For rotational axes, the value is in radians, for prismatic axes it is in meters.
[in] | _index | Index of the axis, defaults to 0. |
[in] | _limit | Lower limit of the axis. |
Reimplemented from Joint.
|
virtual |
Set the velocity of an axis(index).
[in] | _index | Axis index. |
[in] | _vel | Velocity to apply to the joint axis. |
Implements Joint.
|
virtualinherited |
Set the velocity limit on a joint axis.
[in] | _index | Index of the axis to set. |
[in] | _velocity | Velocity limit for the axis. |
|
protectedinherited |
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. |
|
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. |
|
inherited |
Get the string name for the entity type.
|
protectedvirtualinherited |
Unregister items in the introspection service.
|
virtualinherited |
Update the joint.
Reimplemented from Base.
|
virtualinherited |
Update the parameters using new sdf values.
[in] | _sdf | SDF values to update from. |
Reimplemented from Base.
|
virtualinherited |
Get the joint's upper limit.
For rotational axes, the value is in radians. For prismatic axes, it is in meters.
It returns ignition::math::NAN_D in case the limit can't be obtained. For instance, if the index is invalid, if the joint is fixed, etc.
[in] | _index | Index of the axis, defaults to 0. |
Reimplemented in SimbodyJoint, DARTJoint, BulletBallJoint, BulletHinge2Joint, BulletUniversalJoint, BulletHingeJoint, ODEBallJoint, BulletSliderJoint, SimbodyBallJoint, and SimbodyScrewJoint.
|
inherited |
Return the common::URI of this entity.
The URI includes the world where the entity is contained and all the hierarchy of sub-entities that can compose this entity. E.g.: A link entity contains the name of the link and the model where the link is contained.
|
inherited |
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.
|
protectedinherited |
Anchor link.
|
protectedinherited |
Anchor pose.
This is the xyz position of the joint frame specified in the world frame.
|
protectedinherited |
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).
|
protectedinherited |
apply damping for adding viscous damping forces on updates
|
protectedinherited |
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.
|
protectedinherited |
Pointer to Bullet's btDynamicsWorld.
|
protectedinherited |
The first link this joint connects to.
|
protectedinherited |
Children of this entity.
|
protectedinherited |
Pointer to a contraint object in Bullet.
|
protectedinherited |
joint viscous damping coefficient
|
protectedinherited |
Store Joint effort limit as specified in SDF.
|
protectedinherited |
All the introspection items regsitered for this.
|
protectedinherited |
Store Joint position lower limit as specified in SDF.
|
protectedinherited |
Pointer to the parent model.
|
protectedinherited |
Parent of this entity.
|
protectedinherited |
Anchor pose relative to parent link frame.
|
protectedinherited |
The second link this joint connects to.
|
protectedinherited |
Provide Feedback data for contact forces.
|
protectedinherited |
The SDF values for this object.
|
protectedinherited |
joint spring reference (zero load) position
|
protectedinherited |
joint stiffnessCoefficient
|
protectedinherited |
Pitch of the thread.
|
protectedinherited |
Store Joint position upper limit as specified in SDF.
|
protectedinherited |
Store Joint velocity limit as specified in SDF.
|
protectedinherited |
Pointer to the world.
|
protectedinherited |
Cache Joint force torque values in case physics engine clears them at the end of update step.