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 
126  public: void SetState(const JointState &_state);
127 
130  public: void SetModel(ModelPtr _model);
131 
137  public: virtual LinkPtr GetJointLink(unsigned int _index) const = 0;
138 
143  public: virtual bool AreConnected(LinkPtr _one, LinkPtr _two) const = 0;
144 
148  public: virtual void Attach(LinkPtr _parent, LinkPtr _child);
149 
151  public: virtual void Detach();
152 
158  public: virtual void SetAxis(unsigned int _index,
159  const math::Vector3 &_axis) = 0;
160 
165  public: virtual void SetDamping(unsigned int _index, double _damping) = 0;
166 
171  public: double GetDamping(unsigned int _index);
172 
176  public: virtual void ApplyStiffnessDamping();
177 
184  public: virtual void SetStiffnessDamping(unsigned int _index,
185  double _stiffness, double _damping, double _reference = 0) = 0;
186 
192  public: virtual void SetStiffness(unsigned int _index,
193  double _stiffness) = 0;
194 
200  public: double GetStiffness(unsigned int _index);
201 
206  public: double GetSpringReferencePosition(unsigned int _index) const;
207 
211  public: template<typename T>
213  {return jointUpdate.Connect(_subscriber);}
214 
218  {jointUpdate.Disconnect(_conn);}
219 
223  public: math::Vector3 GetLocalAxis(unsigned int _index) const;
224 
228  public: virtual math::Vector3 GetGlobalAxis(
229  unsigned int _index) const = 0;
230 
234  public: virtual void SetAnchor(unsigned int _index,
235  const math::Vector3 &_anchor) = 0;
236 
240  public: virtual math::Vector3 GetAnchor(unsigned int _index) const = 0;
241 
245  public: virtual bool SetHighStop(unsigned int _index,
246  const math::Angle &_angle);
247 
251  public: virtual bool SetLowStop(unsigned int _index,
252  const math::Angle &_angle);
253 
260  public: virtual math::Angle GetHighStop(unsigned int _index) = 0;
261 
268  public: virtual math::Angle GetLowStop(unsigned int _index) = 0;
269 
273  public: virtual double GetEffortLimit(unsigned int _index);
274 
278  public: virtual void SetEffortLimit(unsigned int _index, double _effort);
279 
283  public: virtual double GetVelocityLimit(unsigned int _index);
284 
288  public: virtual void SetVelocityLimit(unsigned int _index,
289  double _velocity);
290 
298  public: virtual void SetVelocity(unsigned int _index, double _vel) = 0;
299 
303  public: virtual double GetVelocity(unsigned int _index) const = 0;
304 
313  public: virtual void SetForce(unsigned int _index, double _effort) = 0;
314 
320  public: double CheckAndTruncateForce(unsigned int _index, double _effort);
321 
328  public: virtual double GetForce(unsigned int _index);
329 
352  public: virtual JointWrench GetForceTorque(unsigned int _index) = 0;
353 
357  public: math::Angle GetAngle(unsigned int _index) const;
358 
361  public: virtual unsigned int GetAngleCount() const = 0;
362 
371  public: virtual bool SetPosition(unsigned int _index, double _position);
372 
381  protected: bool SetPositionMaximal(unsigned int _index, double _position);
382 
390  protected: bool SetVelocityMaximal(unsigned int _index, double _velocity);
391 
398  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const = 0;
399 
406  public: virtual math::Vector3 GetLinkTorque(
407  unsigned int _index) const = 0;
408 
418  public: virtual bool SetParam(const std::string &_key,
419  unsigned int _index,
420  const boost::any &_value) = 0;
421 
426  public: virtual double GetParam(const std::string &_key,
427  unsigned int _index);
428 
431  public: LinkPtr GetChild() const;
432 
435  public: LinkPtr GetParent() const;
436 
439  public: msgs::Joint::Type GetMsgType() const;
440 
443  public: virtual void FillMsg(msgs::Joint &_msg);
444 
452  public: double GetInertiaRatio(const unsigned int _index) const;
453 
463  public: double GetInertiaRatio(const math::Vector3 &_axis) const;
464 
469  public: math::Angle GetLowerLimit(unsigned int _index) const;
470 
475  public: math::Angle GetUpperLimit(unsigned int _index) const;
476 
481  public: void SetLowerLimit(unsigned int _index, math::Angle _limit);
482 
487  public: void SetUpperLimit(unsigned int _index, math::Angle _limit);
488 
491  public: virtual void SetProvideFeedback(bool _enable);
492 
494  public: virtual void CacheForceTorque();
495 
499  public: void SetStopStiffness(unsigned int _index, double _stiffness);
500 
504  public: void SetStopDissipation(unsigned int _index, double _dissipation);
505 
509  public: double GetStopStiffness(unsigned int _index) const;
510 
514  public: double GetStopDissipation(unsigned int _index) const;
515 
519  public: math::Pose GetInitialAnchorPose() const;
520 
525  public: math::Pose GetWorldPose() const;
526 
532  public: math::Pose GetParentWorldPose() const;
533 
539  public: math::Pose GetAnchorErrorPose() const;
540 
546  public: math::Quaternion GetAxisFrame(unsigned int _index) const;
547 
560  public: math::Quaternion GetAxisFrameOffset(unsigned int _index) const;
561 
566  public: double GetWorldEnergyPotentialSpring(unsigned int _index) const;
567 
571  protected: virtual math::Angle GetAngleImpl(
572  unsigned int _index) const = 0;
573 
584  protected: bool FindAllConnectedLinks(const LinkPtr &_originalParentLink,
585  Link_V &_connectedLinks);
586 
592  protected: math::Pose ComputeChildLinkPose(unsigned int _index,
593  double _position);
594 
597  private: void LoadImpl(const math::Pose &_pose);
598 
600  protected: LinkPtr childLink;
601 
603  protected: LinkPtr parentLink;
604 
606  protected: ModelPtr model;
607 
611 
617  protected: math::Pose anchorPose;
618 
621 
623  protected: LinkPtr anchorLink;
624 
626  protected: double dissipationCoefficient[MAX_JOINT_AXIS];
627 
629  protected: double stiffnessCoefficient[MAX_JOINT_AXIS];
630 
632  protected: double springReferencePosition[MAX_JOINT_AXIS];
633 
636 
638  protected: double effortLimit[MAX_JOINT_AXIS];
639 
641  protected: double velocityLimit[MAX_JOINT_AXIS];
642 
644  protected: math::Angle lowerLimit[MAX_JOINT_AXIS];
645 
647  protected: math::Angle upperLimit[MAX_JOINT_AXIS];
648 
651  protected: JointWrench wrench;
652 
656  protected: bool axisParentModelFrame[MAX_JOINT_AXIS];
657 
660  private: static sdf::ElementPtr sdfJoint;
661 
663  protected: bool provideFeedback;
664 
666  private: std::vector<std::string> sensors;
667 
669  private: event::EventT<void ()> jointUpdate;
670 
672  private: math::Angle staticAngle;
673 
675  private: double stopStiffness[MAX_JOINT_AXIS];
676 
678  private: double stopDissipation[MAX_JOINT_AXIS];
679  };
681  }
682 }
683 #endif
ModelPtr model
Pointer to the parent model.
Definition: Joint.hh:606
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:100
Attribute
Joint attribute types.
Definition: Joint.hh:54
Forward declarations for the common classes.
Definition: Animation.hh:33
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
LinkPtr anchorLink
Anchor link.
Definition: Joint.hh:623
High stop angle.
Definition: Joint.hh:84
LinkPtr childLink
The first link this joint connects to.
Definition: Joint.hh:600
Maximum force.
Definition: Joint.hh:78
math::Pose anchorPose
Anchor pose specified in SDF <joint><pose> tag.
Definition: Joint.hh:617
bool provideFeedback
Provide Feedback data for contact forces.
Definition: Joint.hh:663
event::ConnectionPtr ConnectJointUpdate(T _subscriber)
Connect a boost::slot the the joint update signal.
Definition: Joint.hh:212
LinkPtr parentLink
The second link this joint connects to.
Definition: Joint.hh:603
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:651
Base class for most physics classes.
Definition: Base.hh:81
#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:620
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:88
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:217
math::Vector3 anchorPos
Anchor pose.
Definition: Joint.hh:610
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:635
Stop limit error reduction parameter.
Definition: Joint.hh:66
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:216
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:72
Stop limit constraint force mixing.
Definition: Joint.hh:69