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 2012 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 /* Desc: The base joint class
18  * Author: Nate Koenig, Andrew Howard
19  * Date: 21 May 2003
20  */
21 
22 #ifndef _JOINT_HH_
23 #define _JOINT_HH_
24 
25 #include <string>
26 #include <vector>
27 
28 #include <boost/any.hpp>
29 
30 #include "gazebo/common/Event.hh"
31 #include "gazebo/common/Events.hh"
32 #include "gazebo/math/Angle.hh"
33 #include "gazebo/math/Vector3.hh"
34 #include "gazebo/msgs/MessageTypes.hh"
35 
37 #include "gazebo/physics/Base.hh"
39 
43 #define MAX_JOINT_AXIS 2
44 
45 namespace gazebo
46 {
47  namespace physics
48  {
51 
54  class Joint : public Base
55  {
58  public: enum Attribute
59  {
62 
65 
68 
71 
74 
76  ERP,
77 
79  CFM,
80 
83 
85  VEL,
86 
89 
92  };
93 
96  public: explicit Joint(BasePtr _parent);
97 
99  public: virtual ~Joint();
100 
105  public: void Load(LinkPtr _parent, LinkPtr _child,
106  const math::Pose &_pose);
107 
115  public: void Load(LinkPtr _parent, LinkPtr _child,
116  const math::Vector3 &_pos) GAZEBO_DEPRECATED(1.5);
117 
120  public: virtual void Load(sdf::ElementPtr _sdf);
121 
123  public: virtual void Init();
124 
126  public: void Update();
127 
130  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
131 
133  public: virtual void Reset();
134 
137  public: void SetState(const JointState &_state);
138 
141  public: void SetModel(ModelPtr _model);
142 
148  public: virtual LinkPtr GetJointLink(int _index) const = 0;
149 
154  public: virtual bool AreConnected(LinkPtr _one, LinkPtr _two) const = 0;
155 
159  public: virtual void Attach(LinkPtr _parent, LinkPtr _child);
160 
162  public: virtual void Detach();
163 
169  public: virtual void SetAxis(int _index, const math::Vector3 &_axis) = 0;
170 
175  public: virtual void SetDamping(int _index, double _damping) = 0;
176 
181  public: double GetDamping(int _index);
182 
184  public: virtual void ApplyDamping();
185 
189  public: template<typename T>
191  {return jointUpdate.Connect(_subscriber);}
192 
196  {jointUpdate.Disconnect(_conn);}
197 
201  public: math::Vector3 GetLocalAxis(int _index) const;
202 
206  public: virtual math::Vector3 GetGlobalAxis(int _index) const = 0;
207 
211  public: virtual void SetAnchor(int _index,
212  const math::Vector3 &_anchor) = 0;
213 
217  public: virtual math::Vector3 GetAnchor(int _index) const = 0;
218 
222  public: virtual void SetHighStop(int _index,
223  const math::Angle &_angle);
224 
228  public: virtual void SetLowStop(int _index,
229  const math::Angle &_angle);
230 
237  public: virtual math::Angle GetHighStop(int _index) = 0;
238 
245  public: virtual math::Angle GetLowStop(int _index) = 0;
246 
250  public: virtual double GetEffortLimit(int _index);
251 
255  public: virtual double GetVelocityLimit(int _index);
256 
260  public: virtual void SetVelocity(int _index, double _vel) = 0;
261 
265  public: virtual double GetVelocity(int _index) const = 0;
266 
275  public: virtual void SetForce(int _index, double _force);
276 
286  public: virtual double GetForce(int _index) GAZEBO_DEPRECATED(1.5);
287 
297  public: virtual double GetForce(unsigned int _index);
298 
306  public: virtual JointWrench GetForceTorque(int _index)
307  GAZEBO_DEPRECATED(1.5) = 0;
308 
316  public: virtual JointWrench GetForceTorque(unsigned int _index) = 0;
317 
326  public: virtual void SetMaxForce(int _index, double _force) = 0;
327 
336  public: virtual double GetMaxForce(int _index) = 0;
337 
341  public: math::Angle GetAngle(int _index) const;
342 
345  public: virtual unsigned int GetAngleCount() const = 0;
346 
356  public: void SetAngle(int _index, math::Angle _angle);
357 
367  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const = 0;
368 
378  public: virtual math::Vector3 GetLinkTorque(
379  unsigned int _index) const = 0;
380 
386  public: virtual void SetAttribute(const std::string &_key, int _index,
387  const boost::any &_value) = 0;
388 
393  public: virtual double GetAttribute(const std::string &_key,
394  unsigned int _index) = 0;
395 
398  public: LinkPtr GetChild() const;
399 
402  public: LinkPtr GetParent() const;
403 
406  public: void FillMsg(msgs::Joint &_msg);
407 
411  public: double GetInertiaRatio(unsigned int _index) const;
412 
417  public: math::Angle GetLowerLimit(unsigned int _index) const;
418 
423  public: math::Angle GetUpperLimit(unsigned int _index) const;
424 
427  public: virtual void SetProvideFeedback(bool _enable);
428 
432  protected: virtual math::Angle GetAngleImpl(int _index) const = 0;
433 
436  private: void LoadImpl(const math::Pose &_pose);
437 
441  private: void LoadImpl(const math::Vector3 &_pos) GAZEBO_DEPRECATED(1.5);
442 
446  private: void ComputeInertiaRatio();
447 
449  protected: LinkPtr childLink;
450 
452  protected: LinkPtr parentLink;
453 
455  protected: ModelPtr model;
456 
460 
466  protected: math::Pose anchorPose;
467 
469  protected: LinkPtr anchorLink;
470 
472  protected: double dampingCoefficient;
473 
476 
481  protected: double forceApplied[MAX_JOINT_AXIS];
482 
484  protected: double effortLimit[MAX_JOINT_AXIS];
485 
487  protected: double velocityLimit[MAX_JOINT_AXIS];
488 
491  protected: double inertiaRatio[MAX_JOINT_AXIS];
492 
495 
498 
500  protected: bool useCFMDamping;
501 
503  protected: bool provideFeedback;
504 
506  private: std::vector<std::string> sensors;
507 
509  private: event::EventT<void ()> jointUpdate;
510 
512  private: math::Angle staticAngle;
513  };
515  }
516 }
517 #endif