Joint.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 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 GAZEBO_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 
365  public: virtual void SetMaxForce(unsigned int _index, double _force)
366  GAZEBO_DEPRECATED(5.0) = 0;
367 
374  public: virtual double GetMaxForce(unsigned int _index)
375  GAZEBO_DEPRECATED(5.0) = 0;
376 
380  public: math::Angle GetAngle(unsigned int _index) const;
381 
384  public: virtual unsigned int GetAngleCount() const = 0;
385 
396  public: void SetAngle(unsigned int _index, math::Angle _angle)
397  GAZEBO_DEPRECATED(4.0);
398 
407  public: virtual bool SetPosition(unsigned int _index, double _position);
408 
417  protected: bool SetPositionMaximal(unsigned int _index, double _position);
418 
426  protected: bool SetVelocityMaximal(unsigned int _index, double _velocity);
427 
434  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const = 0;
435 
442  public: virtual math::Vector3 GetLinkTorque(
443  unsigned int _index) const = 0;
444 
454  public: virtual bool SetParam(const std::string &_key,
455  unsigned int _index,
456  const boost::any &_value) = 0;
457 
462  public: virtual double GetParam(const std::string &_key,
463  unsigned int _index);
464 
467  public: LinkPtr GetChild() const;
468 
471  public: LinkPtr GetParent() const;
472 
475  public: msgs::Joint::Type GetMsgType() const;
476 
479  public: void FillMsg(msgs::Joint &_msg);
480 
488  public: double GetInertiaRatio(const unsigned int _index) const;
489 
499  public: double GetInertiaRatio(const math::Vector3 &_axis) const;
500 
505  public: math::Angle GetLowerLimit(unsigned int _index) const;
506 
511  public: math::Angle GetUpperLimit(unsigned int _index) const;
512 
517  public: void SetLowerLimit(unsigned int _index, math::Angle _limit);
518 
523  public: void SetUpperLimit(unsigned int _index, math::Angle _limit);
524 
527  public: virtual void SetProvideFeedback(bool _enable);
528 
530  public: virtual void CacheForceTorque();
531 
535  public: void SetStopStiffness(unsigned int _index, double _stiffness);
536 
540  public: void SetStopDissipation(unsigned int _index, double _dissipation);
541 
545  public: double GetStopStiffness(unsigned int _index) const;
546 
550  public: double GetStopDissipation(unsigned int _index) const;
551 
555  public: math::Pose GetInitialAnchorPose() const;
556 
561  public: math::Pose GetWorldPose() const;
562 
568  public: math::Pose GetParentWorldPose() const;
569 
575  public: math::Pose GetAnchorErrorPose() const;
576 
582  public: math::Quaternion GetAxisFrame(unsigned int _index) const;
583 
596  public: math::Quaternion GetAxisFrameOffset(unsigned int _index) const;
597 
602  public: double GetWorldEnergyPotentialSpring(unsigned int _index) const;
603 
607  protected: virtual math::Angle GetAngleImpl(
608  unsigned int _index) const = 0;
609 
620  protected: bool FindAllConnectedLinks(const LinkPtr &_originalParentLink,
621  Link_V &_connectedLinks);
622 
628  protected: math::Pose ComputeChildLinkPose(unsigned int _index,
629  double _position);
630 
633  private: void LoadImpl(const math::Pose &_pose);
634 
636  protected: LinkPtr childLink;
637 
639  protected: LinkPtr parentLink;
640 
642  protected: ModelPtr model;
643 
647 
653  protected: math::Pose anchorPose;
654 
657 
659  protected: LinkPtr anchorLink;
660 
662  protected: double dissipationCoefficient[MAX_JOINT_AXIS];
663 
665  protected: double stiffnessCoefficient[MAX_JOINT_AXIS];
666 
668  protected: double springReferencePosition[MAX_JOINT_AXIS];
669 
672 
674  protected: double effortLimit[MAX_JOINT_AXIS];
675 
677  protected: double velocityLimit[MAX_JOINT_AXIS];
678 
680  protected: math::Angle lowerLimit[MAX_JOINT_AXIS];
681 
683  protected: math::Angle upperLimit[MAX_JOINT_AXIS];
684 
687  protected: JointWrench wrench;
688 
692  protected: bool axisParentModelFrame[MAX_JOINT_AXIS];
693 
696  private: static sdf::ElementPtr sdfJoint;
697 
699  protected: bool provideFeedback;
700 
702  private: std::vector<std::string> sensors;
703 
705  private: event::EventT<void ()> jointUpdate;
706 
708  private: math::Angle staticAngle;
709 
711  private: double stopStiffness[MAX_JOINT_AXIS];
712 
714  private: double stopDissipation[MAX_JOINT_AXIS];
715  };
717  }
718 }
719 #endif
boost::shared_ptr< Connection > ConnectionPtr
Definition: CommonTypes.hh:144
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
Stop limit constraint force mixing.
Definition: Joint.hh:69
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
Error reduction parameter.
Definition: Joint.hh:72
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:40
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:43
Suspension error reduction parameter.
Definition: Joint.hh:60
math::Vector3 anchorPos
Anchor pose.
Definition: Joint.hh:646
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:44
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:186
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:74
#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:41
keeps track of state of a physics::Joint
Definition: JointState.hh:40
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:52
LinkPtr anchorLink
Anchor link.
Definition: Joint.hh:659
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
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