17 #ifndef _GAZEBO_JOINT_HH_
18 #define _GAZEBO_JOINT_HH_
23 #include <boost/any.hpp>
29 #include "gazebo/msgs/MessageTypes.hh"
39 #define MAX_JOINT_AXIS 2
95 public:
virtual ~
Joint();
106 public:
virtual void Load(sdf::ElementPtr _sdf);
109 public:
virtual void Init();
112 public:
virtual void Fini();
115 public:
void Update();
119 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf);
122 public:
virtual void Reset();
127 public:
void SetState(
const JointState &_state);
131 public:
void SetModel(
ModelPtr _model);
138 public:
virtual LinkPtr GetJointLink(
unsigned int _index)
const = 0;
144 public:
virtual bool AreConnected(
LinkPtr _one,
LinkPtr _two)
const = 0;
152 public:
virtual void Detach();
159 public:
virtual void SetAxis(
unsigned int _index,
166 public:
virtual void SetDamping(
unsigned int _index,
double _damping) = 0;
172 public:
double GetDamping(
unsigned int _index);
177 public:
virtual void ApplyStiffnessDamping();
185 public:
virtual void SetStiffnessDamping(
unsigned int _index,
186 double _stiffness,
double _damping,
double _reference = 0) = 0;
193 public:
virtual void SetStiffness(
unsigned int _index,
194 double _stiffness) = 0;
201 public:
double GetStiffness(
unsigned int _index);
207 public:
double GetSpringReferencePosition(
unsigned int _index)
const;
212 public:
template<
typename T>
214 {
return jointUpdate.Connect(_subscriber);}
219 {jointUpdate.Disconnect(_conn);}
224 public:
math::Vector3 GetLocalAxis(
unsigned int _index)
const;
230 unsigned int _index)
const = 0;
235 public:
virtual void SetAnchor(
unsigned int _index,
241 public:
virtual math::Vector3 GetAnchor(
unsigned int _index)
const = 0;
246 public:
virtual bool SetHighStop(
unsigned int _index,
252 public:
virtual bool SetLowStop(
unsigned int _index,
261 public:
virtual math::Angle GetHighStop(
unsigned int _index) = 0;
269 public:
virtual math::Angle GetLowStop(
unsigned int _index) = 0;
274 public:
virtual double GetEffortLimit(
unsigned int _index);
279 public:
virtual void SetEffortLimit(
unsigned int _index,
double _effort);
284 public:
virtual double GetVelocityLimit(
unsigned int _index);
289 public:
virtual void SetVelocityLimit(
unsigned int _index,
299 public:
virtual void SetVelocity(
unsigned int _index,
double _vel) = 0;
304 public:
virtual double GetVelocity(
unsigned int _index)
const = 0;
314 public:
virtual void SetForce(
unsigned int _index,
double _effort) = 0;
321 public:
double CheckAndTruncateForce(
unsigned int _index,
double _effort);
329 public:
virtual double GetForce(
unsigned int _index);
353 public:
virtual JointWrench GetForceTorque(
unsigned int _index) = 0;
358 public:
math::Angle GetAngle(
unsigned int _index)
const;
362 public:
virtual unsigned int GetAngleCount()
const = 0;
372 public:
virtual bool SetPosition(
unsigned int _index,
double _position);
382 protected:
bool SetPositionMaximal(
unsigned int _index,
double _position);
391 protected:
bool SetVelocityMaximal(
unsigned int _index,
double _velocity);
399 public:
virtual math::Vector3 GetLinkForce(
unsigned int _index)
const = 0;
408 unsigned int _index)
const = 0;
419 public:
virtual bool SetParam(
const std::string &_key,
421 const boost::any &_value) = 0;
427 public:
virtual double GetParam(
const std::string &_key,
428 unsigned int _index);
432 public:
LinkPtr GetChild()
const;
436 public:
LinkPtr GetParent()
const;
440 public: msgs::Joint::Type GetMsgType()
const;
444 public:
virtual void FillMsg(msgs::Joint &_msg);
453 public:
double GetInertiaRatio(
const unsigned int _index)
const;
464 public:
double GetInertiaRatio(
const math::Vector3 &_axis)
const;
470 public:
math::Angle GetLowerLimit(
unsigned int _index)
const;
476 public:
math::Angle GetUpperLimit(
unsigned int _index)
const;
482 public:
void SetLowerLimit(
unsigned int _index,
math::Angle _limit);
488 public:
void SetUpperLimit(
unsigned int _index,
math::Angle _limit);
492 public:
virtual void SetProvideFeedback(
bool _enable);
495 public:
virtual void CacheForceTorque();
500 public:
void SetStopStiffness(
unsigned int _index,
double _stiffness);
505 public:
void SetStopDissipation(
unsigned int _index,
double _dissipation);
510 public:
double GetStopStiffness(
unsigned int _index)
const;
515 public:
double GetStopDissipation(
unsigned int _index)
const;
520 public:
math::Pose GetInitialAnchorPose()
const;
533 public:
math::Pose GetParentWorldPose()
const;
540 public:
math::Pose GetAnchorErrorPose()
const;
567 public:
double GetWorldEnergyPotentialSpring(
unsigned int _index)
const;
573 unsigned int _index)
const = 0;
585 protected:
bool FindAllConnectedLinks(
const LinkPtr &_originalParentLink,
593 protected:
math::Pose ComputeChildLinkPose(
unsigned int _index,
598 private:
void LoadImpl(
const math::Pose &_pose);
661 private:
static sdf::ElementPtr sdfJoint;
667 private: std::vector<std::string> sensors;
ModelPtr model
Pointer to the parent model.
Definition: Joint.hh:607
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
Attribute
Joint attribute types.
Definition: Joint.hh:54
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
virtual void Reset()
Reset the object.
LinkPtr anchorLink
Anchor link.
Definition: Joint.hh:624
High stop angle.
Definition: Joint.hh:84
LinkPtr childLink
The first link this joint connects to.
Definition: Joint.hh:601
Maximum force.
Definition: Joint.hh:78
math::Pose anchorPose
Anchor pose specified in SDF <joint><pose> tag.
Definition: Joint.hh:618
bool provideFeedback
Provide Feedback data for contact forces.
Definition: Joint.hh:664
event::ConnectionPtr ConnectJointUpdate(T _subscriber)
Connect a boost::slot the the joint update signal.
Definition: Joint.hh:213
LinkPtr parentLink
The second link this joint connects to.
Definition: Joint.hh:604
Suspension error reduction parameter.
Definition: Joint.hh:60
JointWrench wrench
Cache Joint force torque values in case physics engine clears them at the end of update step...
Definition: Joint.hh:652
Base class for most physics classes.
Definition: Base.hh:77
#define MAX_JOINT_AXIS
maximum number of axis per joint anticipated.
Definition: Joint.hh:39
Constraint force mixing.
Definition: Joint.hh:75
Suspension constraint force mixing.
Definition: Joint.hh:63
A quaternion class.
Definition: Quaternion.hh:42
math::Pose parentAnchorPose
Anchor pose relative to parent link frame.
Definition: Joint.hh:621
keeps track of state of a physics::Joint
Definition: JointState.hh:46
Error reduction parameter.
Definition: Joint.hh:72
Fudge factor.
Definition: Joint.hh:57
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:153
Base class for all joints.
Definition: Joint.hh:50
Velocity.
Definition: Joint.hh:81
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
Wrench information from a joint.
Definition: JointWrench.hh:39
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
void DisconnectJointUpdate(event::ConnectionPtr &_conn)
Disconnect a boost::slot the the joint update signal.
Definition: Joint.hh:218
math::Vector3 anchorPos
Anchor pose.
Definition: Joint.hh:611
An angle and related functions.
Definition: Angle.hh:53
gazebo::event::ConnectionPtr applyDamping
apply damping for adding viscous damping forces on updates
Definition: Joint.hh:636
Stop limit error reduction parameter.
Definition: Joint.hh:66
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:225
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77
Stop limit constraint force mixing.
Definition: Joint.hh:69