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();
126 public:
void SetState(
const JointState &_state);
130 public:
void SetModel(
ModelPtr _model);
137 public:
virtual LinkPtr GetJointLink(
unsigned int _index)
const = 0;
143 public:
virtual bool AreConnected(
LinkPtr _one,
LinkPtr _two)
const = 0;
151 public:
virtual void Detach();
158 public:
virtual void SetAxis(
unsigned int _index,
165 public:
virtual void SetDamping(
unsigned int _index,
double _damping) = 0;
171 public:
double GetDamping(
unsigned int _index);
176 public:
virtual void ApplyStiffnessDamping();
184 public:
virtual void SetStiffnessDamping(
unsigned int _index,
185 double _stiffness,
double _damping,
double _reference = 0) = 0;
192 public:
virtual void SetStiffness(
unsigned int _index,
193 double _stiffness) = 0;
200 public:
double GetStiffness(
unsigned int _index);
206 public:
double GetSpringReferencePosition(
unsigned int _index)
const;
211 public:
template<
typename T>
213 {
return jointUpdate.Connect(_subscriber);}
218 {jointUpdate.Disconnect(_conn);}
223 public:
math::Vector3 GetLocalAxis(
unsigned int _index)
const;
229 unsigned int _index)
const = 0;
234 public:
virtual void SetAnchor(
unsigned int _index,
240 public:
virtual math::Vector3 GetAnchor(
unsigned int _index)
const = 0;
245 public:
virtual bool SetHighStop(
unsigned int _index,
251 public:
virtual bool SetLowStop(
unsigned int _index,
260 public:
virtual math::Angle GetHighStop(
unsigned int _index) = 0;
268 public:
virtual math::Angle GetLowStop(
unsigned int _index) = 0;
273 public:
virtual double GetEffortLimit(
unsigned int _index);
278 public:
virtual void SetEffortLimit(
unsigned int _index,
double _effort);
283 public:
virtual double GetVelocityLimit(
unsigned int _index);
288 public:
virtual void SetVelocityLimit(
unsigned int _index,
298 public:
virtual void SetVelocity(
unsigned int _index,
double _vel) = 0;
303 public:
virtual double GetVelocity(
unsigned int _index)
const = 0;
313 public:
virtual void SetForce(
unsigned int _index,
double _effort) = 0;
320 public:
double CheckAndTruncateForce(
unsigned int _index,
double _effort);
328 public:
virtual double GetForce(
unsigned int _index);
352 public:
virtual JointWrench GetForceTorque(
unsigned int _index) = 0;
365 public:
virtual void SetMaxForce(
unsigned int _index,
double _force)
374 public:
virtual double GetMaxForce(
unsigned int _index)
380 public:
math::Angle GetAngle(
unsigned int _index)
const;
384 public:
virtual unsigned int GetAngleCount()
const = 0;
396 public:
void SetAngle(
unsigned int _index,
math::Angle _angle)
407 public:
virtual bool SetPosition(
unsigned int _index,
double _position);
417 protected:
bool SetPositionMaximal(
unsigned int _index,
double _position);
426 protected:
bool SetVelocityMaximal(
unsigned int _index,
double _velocity);
434 public:
virtual math::Vector3 GetLinkForce(
unsigned int _index)
const = 0;
443 unsigned int _index)
const = 0;
454 public:
virtual bool SetParam(
const std::string &_key,
456 const boost::any &_value) = 0;
462 public:
virtual double GetParam(
const std::string &_key,
463 unsigned int _index);
467 public:
LinkPtr GetChild()
const;
471 public:
LinkPtr GetParent()
const;
475 public: msgs::Joint::Type GetMsgType()
const;
479 public:
void FillMsg(msgs::Joint &_msg);
488 public:
double GetInertiaRatio(
const unsigned int _index)
const;
499 public:
double GetInertiaRatio(
const math::Vector3 &_axis)
const;
505 public:
math::Angle GetLowerLimit(
unsigned int _index)
const;
511 public:
math::Angle GetUpperLimit(
unsigned int _index)
const;
517 public:
void SetLowerLimit(
unsigned int _index,
math::Angle _limit);
523 public:
void SetUpperLimit(
unsigned int _index,
math::Angle _limit);
527 public:
virtual void SetProvideFeedback(
bool _enable);
530 public:
virtual void CacheForceTorque();
535 public:
void SetStopStiffness(
unsigned int _index,
double _stiffness);
540 public:
void SetStopDissipation(
unsigned int _index,
double _dissipation);
545 public:
double GetStopStiffness(
unsigned int _index)
const;
550 public:
double GetStopDissipation(
unsigned int _index)
const;
555 public:
math::Pose GetInitialAnchorPose()
const;
568 public:
math::Pose GetParentWorldPose()
const;
575 public:
math::Pose GetAnchorErrorPose()
const;
602 public:
double GetWorldEnergyPotentialSpring(
unsigned int _index)
const;
608 unsigned int _index)
const = 0;
620 protected:
bool FindAllConnectedLinks(
const LinkPtr &_originalParentLink,
628 protected:
math::Pose ComputeChildLinkPose(
unsigned int _index,
633 private:
void LoadImpl(
const math::Pose &_pose);
696 private:
static sdf::ElementPtr sdfJoint;
702 private: std::vector<std::string> sensors;
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:147
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:68
Stop limit constraint force mixing.
Definition: Joint.hh:69
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
Error reduction parameter.
Definition: Joint.hh:72
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
LinkPtr parentLink
The second link this joint connects to.
Definition: Joint.hh:639
Maximum force.
Definition: Joint.hh:78
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
LinkPtr childLink
The first link this joint connects to.
Definition: Joint.hh:636
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
Suspension error reduction parameter.
Definition: Joint.hh:60
math::Vector3 anchorPos
Anchor pose.
Definition: Joint.hh:646
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:47
math::Pose anchorPose
Anchor pose specified in SDF <joint><pose> tag.
Definition: Joint.hh:653
ModelPtr model
Pointer to the parent model.
Definition: Joint.hh:642
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:196
JointWrench wrench
Cache Joint force torque values in case physics engine clears them at the end of update step...
Definition: Joint.hh:687
High stop angle.
Definition: Joint.hh:84
Constraint force mixing.
Definition: Joint.hh:75
Velocity.
Definition: Joint.hh:81
event::ConnectionPtr ConnectJointUpdate(T _subscriber)
Connect a boost::slot the the joint update signal.
Definition: Joint.hh:212
Suspension constraint force mixing.
Definition: Joint.hh:63
Fudge factor.
Definition: Joint.hh:57
Base class for most physics classes.
Definition: Base.hh:80
#define MAX_JOINT_AXIS
maximum number of axis per joint anticipated.
Definition: Joint.hh:39
bool provideFeedback
Provide Feedback data for contact forces.
Definition: Joint.hh:699
A quaternion class.
Definition: Quaternion.hh:42
keeps track of state of a physics::Joint
Definition: JointState.hh:46
Stop limit error reduction parameter.
Definition: Joint.hh:66
Base class for all joints.
Definition: Joint.hh:50
Attribute
Joint attribute types.
Definition: Joint.hh:54
Wrench information from a joint.
Definition: JointWrench.hh:39
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
An angle and related functions.
Definition: Angle.hh:53
LinkPtr anchorLink
Anchor link.
Definition: Joint.hh:659
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92
gazebo::event::ConnectionPtr applyDamping
apply damping for adding viscous damping forces on updates
Definition: Joint.hh:671
void DisconnectJointUpdate(event::ConnectionPtr &_conn)
Disconnect a boost::slot the the joint update signal.
Definition: Joint.hh:217
math::Pose parentAnchorPose
Anchor pose relative to parent link frame.
Definition: Joint.hh:656