All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
DARTJoint.hh
Go to the documentation of this file.
1 /*
2  * Copyright 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 
18 #ifndef _GAZEBO_DARTJOINT_HH_
19 #define _GAZEBO_DARTJOINT_HH_
20 
21 #include <boost/any.hpp>
22 #include <string>
23 
25 #include "gazebo/physics/Joint.hh"
28 #include "gazebo/util/system.hh"
29 
30 namespace gazebo
31 {
32  namespace physics
33  {
36  {
39  public: DARTJoint(BasePtr _parent);
40 
42  public: virtual ~DARTJoint();
43 
44  // Documentation inherited.
45  public: virtual void Load(sdf::ElementPtr _sdf);
46 
48  public: virtual void Init();
49 
50  // Documentation inherited.
51  public: virtual void Reset();
52 
53  // Documentation inherited.
54  public: virtual LinkPtr GetJointLink(unsigned int _index) const;
55 
56  // Documentation inherited.
57  public: virtual bool AreConnected(LinkPtr _one, LinkPtr _two) const;
58 
59  // Documentation inherited.
60  public: virtual void Attach(LinkPtr _parent, LinkPtr _child);
61 
62  // Documentation inherited.
63  public: virtual void Detach();
64 
66  public: virtual void SetAnchor(unsigned int /*_index*/,
67  const gazebo::math::Vector3 &/*_anchor*/);
68 
69  // Documentation inherited
70  public: virtual void SetDamping(unsigned int _index, double _damping);
71 
72  // Documentation inherited.
73  public: virtual void SetStiffness(unsigned int _index,
74  const double _stiffness);
75 
76  // Documentation inherited.
77  public: virtual void SetStiffnessDamping(unsigned int _index,
78  double _stiffness, double _damping, double _reference = 0);
79 
80  // Documentation inherited.
81  public: virtual bool SetHighStop(unsigned int _index,
82  const math::Angle &_angle);
83 
84  // Documentation inherited.
85  public: virtual bool SetLowStop(unsigned int _index,
86  const math::Angle &_angle);
87 
88  // Documentation inherited.
89  public: virtual math::Angle GetHighStop(unsigned int _index);
90 
91  // Documentation inherited.
92  public: virtual math::Angle GetLowStop(unsigned int _index);
93 
94  // Documentation inherited.
95  public: virtual math::Vector3 GetLinkForce(unsigned int _index) const;
96 
97  // Documentation inherited.
98  public: virtual math::Vector3 GetLinkTorque(unsigned int _index) const;
99 
100  // Documentation inherited.
101  public: virtual bool SetParam(const std::string &_key,
102  unsigned int _index,
103  const boost::any &_value);
104 
105  // Documentation inherited.
106  public: virtual double GetParam(const std::string &_key,
107  unsigned int _index);
108 
109  // Documentation inherited.
110  public: virtual JointWrench GetForceTorque(unsigned int _index);
111 
112  // Documentation inherited.
113  public: virtual void SetForce(unsigned int _index, double _force);
114 
115  // Documentation inherited.
116  public: virtual double GetForce(unsigned int _index);
117 
118  // Documentation inherited.
119  public: virtual unsigned int GetAngleCount() const;
120 
121  // Documentation inherited.
122  public: virtual void ApplyDamping();
123 
132  protected: virtual void SetForceImpl(unsigned int _index,
133  double _force) = 0;
134 
138  private: void SaveForce(unsigned int _index, double _force);
139 
142  public: DARTModelPtr GetDARTModel() const;
143 
146  public: dart::dynamics::Joint *GetDARTJoint();
147 
153  private: double forceApplied[MAX_JOINT_AXIS];
154 
157  private: common::Time forceAppliedTime;
158 
161 
163  protected: dart::dynamics::Joint *dtJoint;
164 
166  protected: dart::dynamics::BodyNode *dtChildBodyNode;
167  };
168  }
169 }
170 #endif
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
dart::dynamics::Joint * dtJoint
DART joint pointer.
Definition: DARTJoint.hh:163
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
boost::shared_ptr< DARTPhysics > DARTPhysicsPtr
Definition: DARTTypes.hh:39
DARTPhysicsPtr dartPhysicsEngine
DARTPhysics engine pointer.
Definition: DARTJoint.hh:160
boost::shared_ptr< DARTModel > DARTModelPtr
Definition: DARTTypes.hh:42
#define MAX_JOINT_AXIS
maximum number of axis per joint anticipated.
Definition: Joint.hh:39
Base class for all joints.
Definition: Joint.hh:50
Wrench information from a joint.
Definition: JointWrench.hh:39
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
DART joint interface.
Definition: DARTJoint.hh:35
An angle and related functions.
Definition: Angle.hh:52
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:43
dart::dynamics::BodyNode * dtChildBodyNode
DART child body node pointer.
Definition: DARTJoint.hh:166