All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Joint.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2014 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 
175  public: virtual void ApplyDamping() GAZEBO_DEPRECATED(3.0);
176 
180  public: virtual void ApplyStiffnessDamping();
181 
188  public: virtual void SetStiffnessDamping(unsigned int _index,
189  double _stiffness, double _damping, double _reference = 0) = 0;
190 
196  public: virtual void SetStiffness(unsigned int _index,
197  double _stiffness) = 0;
198 
204  public: double GetStiffness(unsigned int _index);
205 
210  public: double GetSpringReferencePosition(unsigned int _index) const;
211 
215  public: template<typename T>
216  event::ConnectionPtr ConnectJointUpdate(T _subscriber)
217  {return jointUpdate.Connect(_subscriber);}
218 
222  {jointUpdate.Disconnect(_conn);}
223 
227  public: math::Vector3 GetLocalAxis(unsigned int _index) const;
228 
232  public: virtual math::Vector3 GetGlobalAxis(
233  unsigned int _index) const = 0;
234 
238  public: virtual void SetAnchor(unsigned int _index,
239  const math::Vector3 &_anchor) = 0;
240 
244  public: virtual math::Vector3 GetAnchor(unsigned int _index) const = 0;
245 
249  public: virtual bool SetHighStop(unsigned int _index,
250  const math::Angle &_angle);
251 
255  public: virtual bool SetLowStop(unsigned int _index,
256  const math::Angle &_angle);
257 
264  public: virtual math::Angle GetHighStop(unsigned int _index) = 0;
265 
272  public: virtual math::Angle GetLowStop(unsigned int _index) = 0;
273 
277  public: virtual double GetEffortLimit(unsigned int _index);
278 
282  public: virtual void SetEffortLimit(unsigned int _index, double _effort);
283 
287  public: virtual double GetVelocityLimit(unsigned int _index);
288 
292  public: virtual void SetVelocity(unsigned int _index, double _vel) = 0;
293 
297  public: virtual double GetVelocity(unsigned int _index) const = 0;
298 
307  public: virtual void SetForce(unsigned int _index, double _effort) = 0;
308 
314  public: double CheckAndTruncateForce(unsigned int _index, double _effort);
315 
322  public: virtual double GetForce(unsigned int _index);
323 
346  public: virtual JointWrench GetForceTorque(unsigned int _index) = 0;
347 
353  public: virtual void SetMaxForce(unsigned int _index, double _force) = 0;
354 
360  public: virtual double GetMaxForce(unsigned int _index) = 0;
361 
365  public: math::Angle GetAngle(unsigned int _index) const;
366 
369  public: virtual unsigned int GetAngleCount() const = 0;
370 
380  public: void SetAngle(unsigned int _index, math::Angle _angle);
381 
388  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const = 0;
389 
396  public: virtual math::Vector3 GetLinkTorque(
397  unsigned int _index) const = 0;
398 
404  public: virtual bool SetParam(const std::string &_key,
405  unsigned int _index,
406  const boost::any &_value) = 0;
407 
414  public: virtual void SetAttribute(const std::string &_key,
415  unsigned int _index,
416  const boost::any &_value)
417  GAZEBO_DEPRECATED(3.0) = 0;
418 
422  public: virtual double GetParam(const std::string &_key,
423  unsigned int _index) = 0;
424 
429  public: virtual double GetAttribute(const std::string &_key,
430  unsigned int _index) GAZEBO_DEPRECATED(3.0) = 0;
431 
434  public: LinkPtr GetChild() const;
435 
438  public: LinkPtr GetParent() const;
439 
442  public: void FillMsg(msgs::Joint &_msg);
443 
451  public: double GetInertiaRatio(const unsigned int _index) const;
452 
462  public: double GetInertiaRatio(const math::Vector3 &_axis) const;
463 
468  public: math::Angle GetLowerLimit(unsigned int _index) const;
469 
474  public: math::Angle GetUpperLimit(unsigned int _index) const;
475 
480  public: void SetLowerLimit(unsigned int _index, math::Angle _limit);
481 
486  public: void SetUpperLimit(unsigned int _index, math::Angle _limit);
487 
490  public: virtual void SetProvideFeedback(bool _enable);
491 
493  public: virtual void CacheForceTorque() { }
494 
498  public: double GetDampingCoefficient() const GAZEBO_DEPRECATED(3.0);
499 
503  public: void SetStopStiffness(unsigned int _index, double _stiffness);
504 
508  public: void SetStopDissipation(unsigned int _index, double _dissipation);
509 
513  public: double GetStopStiffness(unsigned int _index) const;
514 
518  public: double GetStopDissipation(unsigned int _index) const;
519 
523  public: math::Pose GetInitialAnchorPose() const;
524 
529  public: math::Pose GetWorldPose() const;
530 
536  public: math::Pose GetParentWorldPose() const;
537 
543  public: math::Pose GetAnchorErrorPose() const;
544 
550  public: math::Quaternion GetAxisFrame(unsigned int _index) const;
551 
556  public: double GetWorldEnergyPotentialSpring(unsigned int _index) const;
557 
561  protected: virtual math::Angle GetAngleImpl(
562  unsigned int _index) const = 0;
563 
566  private: void LoadImpl(const math::Pose &_pose);
567 
569  protected: LinkPtr childLink;
570 
572  protected: LinkPtr parentLink;
573 
575  protected: ModelPtr model;
576 
579  protected: math::Vector3 anchorPos;
580 
586  protected: math::Pose anchorPose;
587 
589  protected: math::Pose parentAnchorPose;
590 
592  protected: LinkPtr anchorLink;
593 
596  protected: double dampingCoefficient;
597 
600  protected: double dissipationCoefficient[MAX_JOINT_AXIS];
601 
603  protected: double stiffnessCoefficient[MAX_JOINT_AXIS];
604 
606  protected: double springReferencePosition[MAX_JOINT_AXIS];
607 
609  protected: gazebo::event::ConnectionPtr applyDamping;
610 
612  protected: double effortLimit[MAX_JOINT_AXIS];
613 
615  protected: double velocityLimit[MAX_JOINT_AXIS];
616 
618  protected: math::Angle lowerLimit[MAX_JOINT_AXIS];
619 
621  protected: math::Angle upperLimit[MAX_JOINT_AXIS];
622 
625  protected: JointWrench wrench;
626 
630  protected: bool useCFMDamping;
631 
635  protected: bool axisParentModelFrame[MAX_JOINT_AXIS];
636 
639  private: static sdf::ElementPtr sdfJoint;
640 
642  protected: bool provideFeedback;
643 
645  private: std::vector<std::string> sensors;
646 
648  private: event::EventT<void ()> jointUpdate;
649 
651  private: math::Angle staticAngle;
652 
654  private: double stopStiffness[MAX_JOINT_AXIS];
655 
657  private: double stopDissipation[MAX_JOINT_AXIS];
658  };
660  }
661 }
662 #endif