|  | 
|  | BulletScrewJoint (btDynamicsWorld *_world, BasePtr _parent) | 
|  | Constructor.  More... 
 | 
|  | 
| virtual | ~BulletScrewJoint () | 
|  | Destructor.  More... 
 | 
|  | 
| virtual math::Vector3 | GetAnchor (unsigned int _index) const | 
|  | Get the anchor point.  More... 
 | 
|  | 
| virtual math::Vector3 | GetGlobalAxis (unsigned int _index) const | 
|  | Get the axis of rotation.  More... 
 | 
|  | 
| virtual double | GetMaxForce (unsigned int _index) | 
|  | Get the max allowed force of an axis(index).  More... 
 | 
|  | 
| virtual double | GetParam (const std::string &_key, unsigned int _index) | 
|  | Get a non-generic parameter for the joint.  More... 
 | 
|  | 
| virtual double | GetThreadPitch (unsigned int _index) | 
|  | 
| virtual double | GetThreadPitch () | 
|  | Get screw joint thread pitch.  More... 
 | 
|  | 
| virtual double | GetVelocity (unsigned int _index) const | 
|  | Get the rate of change.  More... 
 | 
|  | 
| virtual void | Init () | 
|  | Initialize joint.  More... 
 | 
|  | 
| virtual void | Load (sdf::ElementPtr _sdf) | 
|  | Load the BulletScrewJoint.  More... 
 | 
|  | 
| virtual void | SetAnchor (unsigned int _index, const math::Vector3 &_anchor) | 
|  | Set the anchor point.  More... 
 | 
|  | 
| void | SetAxis (unsigned int _index, const math::Vector3 &_axis) | 
|  | Set the axis of motion.  More... 
 | 
|  | 
| virtual bool | SetHighStop (unsigned int _index, const math::Angle &_angle) | 
|  | Set the high stop of an axis(index).  More... 
 | 
|  | 
| virtual bool | SetLowStop (unsigned int _index, const math::Angle &_angle) | 
|  | Set the low stop of an axis(index).  More... 
 | 
|  | 
| virtual void | SetMaxForce (unsigned int _index, double _force) | 
|  | Set the max allowed force of an axis(index).  More... 
 | 
|  | 
| virtual void | SetThreadPitch (unsigned int _index, double _threadPitch) | 
|  | 
| virtual void | SetThreadPitch (double _threadPitch) | 
|  | Set screw joint thread pitch.  More... 
 | 
|  | 
| virtual void | SetVelocity (unsigned int _index, double _vel) | 
|  | Set the velocity of an axis(index).  More... 
 | 
|  | 
|  | ScrewJoint (BasePtr _parent) | 
|  | Constructor.  More... 
 | 
|  | 
| virtual | ~ScrewJoint () | 
|  | Destructor.  More... 
 | 
|  | 
| virtual unsigned int | GetAngleCount () const | 
|  | 
|  | BulletJoint (BasePtr _parent) | 
|  | Constructor.  More... 
 | 
|  | 
| virtual | ~BulletJoint () | 
|  | Destructor.  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 | CacheForceTorque () | 
|  | Cache Joint Force Torque Values if necessary for physics engine.  More... 
 | 
|  | 
| virtual void | Detach () | 
|  | Detach this joint from all bodies.  More... 
 | 
|  | 
| virtual double | GetForce (unsigned int _index) | 
|  | 
| virtual JointWrench | GetForceTorque (unsigned int _index) | 
|  | get internal force and torque values at a joint.  More... 
 | 
|  | 
| virtual math::Angle | GetHighStop (unsigned int _index) | 
|  | Get the high stop of an axis(index).  More... 
 | 
|  | 
| LinkPtr | GetJointLink (unsigned int _index) const | 
|  | Get the body to which the joint is attached according the _index.  More... 
 | 
|  | 
| virtual math::Vector3 | GetLinkForce (unsigned int _index) const | 
|  | Get the force the joint applies to the first body.  More... 
 | 
|  | 
| virtual math::Vector3 | GetLinkTorque (unsigned int _index) const | 
|  | Get the torque the joint applies to the first body.  More... 
 | 
|  | 
| virtual math::Angle | GetLowStop (unsigned int _index) | 
|  | Get the low stop of an axis(index).  More... 
 | 
|  | 
| virtual void | Reset () | 
|  | Reset the joint.  More... 
 | 
|  | 
| virtual void | SetDamping (unsigned int _index, double _damping) | 
|  | Set the joint damping.  More... 
 | 
|  | 
| virtual void | SetForce (unsigned int _index, double _force) | 
|  | Set the force applied to this physics::Joint.  More... 
 | 
|  | 
| virtual bool | SetParam (const std::string &_key, unsigned int _index, const boost::any &_value) | 
|  | Set a non-generic parameter for the joint.  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... 
 | 
|  | 
| 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... 
 | 
|  | 
|  | Joint (BasePtr _parent) | 
|  | Constructor.  More... 
 | 
|  | 
| virtual | ~Joint () | 
|  | Destructor.  More... 
 | 
|  | 
| virtual void | Attach (LinkPtr _parent, LinkPtr _child) | 
|  | Attach the two bodies with this joint.  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... 
 | 
|  | 
| void | DisconnectJointUpdate (event::ConnectionPtr &_conn) | 
|  | Disconnect a boost::slot the the joint update signal.  More... 
 | 
|  | 
| void | FillMsg (msgs::Joint &_msg) | 
|  | Fill a joint message.  More... 
 | 
|  | 
| virtual void | Fini () | 
|  | Finialize the object.  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... 
 | 
|  | 
| 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... 
 | 
|  | 
| LinkPtr | GetChild () const | 
|  | Get the child link.  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... 
 | 
|  | 
| 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| msgs::Joint::Type | GetMsgType () const | 
|  | Get the joint type as msgs::Joint::Type.  More... 
 | 
|  | 
| LinkPtr | GetParent () const | 
|  | Get the parent link.  More... 
 | 
|  | 
| math::Pose | GetParentWorldPose () const | 
|  | Get anchor pose on parent link relative to world frame.  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... 
 | 
|  | 
| math::Angle | GetUpperLimit (unsigned int _index) const | 
|  | : get the joint lower limit (replacee GetLowStop and GetHighStop)  More... 
 | 
|  | 
| virtual double | GetVelocityLimit (unsigned int _index) | 
|  | Get the velocity limit on axis(index).  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... 
 | 
|  | 
| void | Load (LinkPtr _parent, LinkPtr _child, const math::Pose &_pose) | 
|  | Set pose, parent and child links of a physics::Joint.  More... 
 | 
|  | 
| void | SetAngle (unsigned int _index, math::Angle _angle) GAZEBO_DEPRECATED(4.0) | 
|  | If the Joint is static, Gazebo stores the state of this Joint as a scalar inside the Joint class, so this call will NOT move the joint dynamically for a static Model.  More... 
 | 
|  | 
| virtual void | SetEffortLimit (unsigned int _index, double _effort) | 
|  | Set the effort limit on a joint axis.  More... 
 | 
|  | 
| void | SetLowerLimit (unsigned int _index, math::Angle _limit) | 
|  | : set the joint upper limit (replaces SetLowStop and SetHighStop)  More... 
 | 
|  | 
| void | SetModel (ModelPtr _model) | 
|  | Set the model this joint belongs too.  More... 
 | 
|  | 
| void | SetState (const JointState &_state) | 
|  | Set the joint state.  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 | SetVelocityLimit (unsigned int _index, double _velocity) | 
|  | Set the velocity limit on a joint axis.  More... 
 | 
|  | 
| void | Update () | 
|  | Update the joint.  More... 
 | 
|  | 
| virtual void | UpdateParameters (sdf::ElementPtr _sdf) | 
|  | Update the parameters using new sdf values.  More... 
 | 
|  | 
|  | Base (BasePtr _parent) | 
|  | Constructor.  More... 
 | 
|  | 
| virtual | ~Base () | 
|  | Destructor.  More... 
 | 
|  | 
| void | AddChild (BasePtr _child) | 
|  | Add a child to this entity.  More... 
 | 
|  | 
| void | AddType (EntityType _type) | 
|  | Add a type specifier.  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... 
 | 
|  | 
| unsigned int | GetChildCount () const | 
|  | Get the number of children.  More... 
 | 
|  | 
| uint32_t | GetId () const | 
|  | Return the ID of this entity.  More... 
 | 
|  | 
| std::string | GetName () const | 
|  | Return the name of the entity.  More... 
 | 
|  | 
| BasePtr | GetParent () const | 
|  | Get the parent.  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... 
 | 
|  | 
| unsigned int | GetType () const | 
|  | Get the full type definition.  More... 
 | 
|  | 
| const WorldPtr & | GetWorld () const | 
|  | Get the World this object is in.  More... 
 | 
|  | 
| bool | HasType (const EntityType &_t) const | 
|  | Returns true if this object's type definition has the given type.  More... 
 | 
|  | 
| bool | IsSelected () const | 
|  | True if the entity is selected by the user.  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 | RemoveChildren () | 
|  | Remove all children.  More... 
 | 
|  | 
| virtual void | Reset (Base::EntityType _resetType) | 
|  | Calls recursive Reset on one of the Base::EntityType's.  More... 
 | 
|  | 
| virtual void | SetName (const std::string &_name) | 
|  | Set the name of the entity.  More... 
 | 
|  | 
| void | SetParent (BasePtr _parent) | 
|  | Set the parent.  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 | SetWorld (const WorldPtr &_newWorld) | 
|  | Set the world this object belongs to.  More... 
 | 
|  |