Joint.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GAZEBO_JOINT_HH_
18 #define _GAZEBO_JOINT_HH_
19 
20 #include <string>
21 #include <vector>
22 
23 #include <boost/any.hpp>
24 
25 #include "gazebo/common/Event.hh"
26 #include "gazebo/common/Events.hh"
27 #include "gazebo/math/Angle.hh"
28 #include "gazebo/math/Vector3.hh"
29 #include "gazebo/msgs/MessageTypes.hh"
30 
32 #include "gazebo/physics/Base.hh"
34 #include "gazebo/util/system.hh"
35 
39 #define MAX_JOINT_AXIS 2
40 
41 namespace gazebo
42 {
43  namespace physics
44  {
47 
50  class GZ_PHYSICS_VISIBLE Joint : public Base
51  {
54  public: enum Attribute
55  {
58 
61 
64 
67 
70 
72  ERP,
73 
75  CFM,
76 
79 
81  VEL,
82 
85 
87  LO_STOP
88  };
89 
92  public: explicit Joint(BasePtr _parent);
93 
95  public: virtual ~Joint();
96 
101  public: void Load(LinkPtr _parent, LinkPtr _child,
102  const math::Pose &_pose);
103 
106  public: virtual void Load(sdf::ElementPtr _sdf);
107 
109  public: virtual void Init();
110 
112  public: virtual void Fini();
113 
115  public: void Update();
116 
119  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
120 
122  public: virtual void Reset();
123  using Base::Reset;
124 
127  public: void SetState(const JointState &_state);
128 
131  public: void SetModel(ModelPtr _model);
132 
138  public: virtual LinkPtr GetJointLink(unsigned int _index) const = 0;
139 
144  public: virtual bool AreConnected(LinkPtr _one, LinkPtr _two) const = 0;
145 
149  public: virtual void Attach(LinkPtr _parent, LinkPtr _child);
150 
152  public: virtual void Detach();
153 
159  public: virtual void SetAxis(unsigned int _index,
160  const math::Vector3 &_axis) = 0;
161 
166  public: virtual void SetDamping(unsigned int _index, double _damping) = 0;
167 
172  public: double GetDamping(unsigned int _index);
173 
177  public: virtual void ApplyStiffnessDamping();
178 
185  public: virtual void SetStiffnessDamping(unsigned int _index,
186  double _stiffness, double _damping, double _reference = 0) = 0;
187 
193  public: virtual void SetStiffness(unsigned int _index,
194  double _stiffness) = 0;
195 
201  public: double GetStiffness(unsigned int _index);
202 
207  public: double GetSpringReferencePosition(unsigned int _index) const;
208 
212  public: template<typename T>
214  {return jointUpdate.Connect(_subscriber);}
215 
219  {jointUpdate.Disconnect(_conn);}
220 
224  public: math::Vector3 GetLocalAxis(unsigned int _index) const;
225 
229  public: virtual math::Vector3 GetGlobalAxis(
230  unsigned int _index) const = 0;
231 
235  public: virtual void SetAnchor(unsigned int _index,
236  const math::Vector3 &_anchor) = 0;
237 
241  public: virtual math::Vector3 GetAnchor(unsigned int _index) const = 0;
242 
246  public: virtual bool SetHighStop(unsigned int _index,
247  const math::Angle &_angle);
248 
252  public: virtual bool SetLowStop(unsigned int _index,
253  const math::Angle &_angle);
254 
261  public: virtual math::Angle GetHighStop(unsigned int _index) = 0;
262 
269  public: virtual math::Angle GetLowStop(unsigned int _index) = 0;
270 
274  public: virtual double GetEffortLimit(unsigned int _index);
275 
279  public: virtual void SetEffortLimit(unsigned int _index, double _effort);
280 
284  public: virtual double GetVelocityLimit(unsigned int _index);
285 
289  public: virtual void SetVelocityLimit(unsigned int _index,
290  double _velocity);
291 
299  public: virtual void SetVelocity(unsigned int _index, double _vel) = 0;
300 
304  public: virtual double GetVelocity(unsigned int _index) const = 0;
305 
314  public: virtual void SetForce(unsigned int _index, double _effort) = 0;
315 
321  public: double CheckAndTruncateForce(unsigned int _index, double _effort);
322 
329  public: virtual double GetForce(unsigned int _index);
330 
353  public: virtual JointWrench GetForceTorque(unsigned int _index) = 0;
354 
358  public: math::Angle GetAngle(unsigned int _index) const;
359 
362  public: virtual unsigned int GetAngleCount() const = 0;
363 
372  public: virtual bool SetPosition(unsigned int _index, double _position);
373 
382  protected: bool SetPositionMaximal(unsigned int _index, double _position);
383 
391  protected: bool SetVelocityMaximal(unsigned int _index, double _velocity);
392 
399  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const = 0;
400 
407  public: virtual math::Vector3 GetLinkTorque(
408  unsigned int _index) const = 0;
409 
419  public: virtual bool SetParam(const std::string &_key,
420  unsigned int _index,
421  const boost::any &_value) = 0;
422 
427  public: virtual double GetParam(const std::string &_key,
428  unsigned int _index);
429 
432  public: LinkPtr GetChild() const;
433 
436  public: LinkPtr GetParent() const;
437 
440  public: msgs::Joint::Type GetMsgType() const;
441 
444  public: virtual void FillMsg(msgs::Joint &_msg);
445 
453  public: double GetInertiaRatio(const unsigned int _index) const;
454 
464  public: double GetInertiaRatio(const math::Vector3 &_axis) const;
465 
470  public: math::Angle GetLowerLimit(unsigned int _index) const;
471 
476  public: math::Angle GetUpperLimit(unsigned int _index) const;
477 
482  public: void SetLowerLimit(unsigned int _index, math::Angle _limit);
483 
488  public: void SetUpperLimit(unsigned int _index, math::Angle _limit);
489 
492  public: virtual void SetProvideFeedback(bool _enable);
493 
495  public: virtual void CacheForceTorque();
496 
500  public: void SetStopStiffness(unsigned int _index, double _stiffness);
501 
505  public: void SetStopDissipation(unsigned int _index, double _dissipation);
506 
510  public: double GetStopStiffness(unsigned int _index) const;
511 
515  public: double GetStopDissipation(unsigned int _index) const;
516 
520  public: math::Pose GetInitialAnchorPose() const;
521 
526  public: math::Pose GetWorldPose() const;
527 
533  public: math::Pose GetParentWorldPose() const;
534 
540  public: math::Pose GetAnchorErrorPose() const;
541 
547  public: math::Quaternion GetAxisFrame(unsigned int _index) const;
548 
561  public: math::Quaternion GetAxisFrameOffset(unsigned int _index) const;
562 
567  public: double GetWorldEnergyPotentialSpring(unsigned int _index) const;
568 
572  protected: virtual math::Angle GetAngleImpl(
573  unsigned int _index) const = 0;
574 
585  protected: bool FindAllConnectedLinks(const LinkPtr &_originalParentLink,
586  Link_V &_connectedLinks);
587 
593  protected: math::Pose ComputeChildLinkPose(unsigned int _index,
594  double _position);
595 
598  private: void LoadImpl(const math::Pose &_pose);
599 
601  protected: LinkPtr childLink;
602 
604  protected: LinkPtr parentLink;
605 
607  protected: ModelPtr model;
608 
612 
618  protected: math::Pose anchorPose;
619 
622 
624  protected: LinkPtr anchorLink;
625 
627  protected: double dissipationCoefficient[MAX_JOINT_AXIS];
628 
630  protected: double stiffnessCoefficient[MAX_JOINT_AXIS];
631 
633  protected: double springReferencePosition[MAX_JOINT_AXIS];
634 
637 
639  protected: double effortLimit[MAX_JOINT_AXIS];
640 
642  protected: double velocityLimit[MAX_JOINT_AXIS];
643 
645  protected: math::Angle lowerLimit[MAX_JOINT_AXIS];
646 
648  protected: math::Angle upperLimit[MAX_JOINT_AXIS];
649 
652  protected: JointWrench wrench;
653 
657  protected: bool axisParentModelFrame[MAX_JOINT_AXIS];
658 
661  private: static sdf::ElementPtr sdfJoint;
662 
664  protected: bool provideFeedback;
665 
667  private: std::vector<std::string> sensors;
668 
670  private: event::EventT<void ()> jointUpdate;
671 
673  private: math::Angle staticAngle;
674 
676  private: double stopStiffness[MAX_JOINT_AXIS];
677 
679  private: double stopDissipation[MAX_JOINT_AXIS];
680  };
682  }
683 }
684 #endif
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