ODEPhysics.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 _ODEPHYSICS_HH_
18 #define _ODEPHYSICS_HH_
19 
20 #include <tbb/spin_mutex.h>
21 #include <tbb/concurrent_vector.h>
22 #include <map>
23 #include <string>
24 #include <vector>
25 #include <utility>
26 
27 #include <boost/thread/thread.hpp>
28 
33 #include "gazebo/physics/Shape.hh"
34 #include "gazebo/gazebo_config.h"
35 #include "gazebo/util/system.hh"
36 
37 namespace gazebo
38 {
39  namespace physics
40  {
43  {
44  public: ODEJointFeedback() : contact(NULL), count(0) {}
45 
47  public: Contact *contact;
48 
50  public: int count;
51 
53  public: dJointFeedback feedbacks[MAX_CONTACT_JOINTS];
54  };
55 
58  {
61  public: enum ODEParam
62  {
65 
68 
71 
74 
77 
79  SOR,
80 
83 
86 
89 
92 
95  INERTIA_RATIO_REDUCTION
96  };
97 
100  public: ODEPhysics(WorldPtr _world);
101 
103  public: virtual ~ODEPhysics();
104 
105  // Documentation inherited
106  public: virtual void Load(sdf::ElementPtr _sdf);
107 
108  // Documentation inherited
109  public: virtual void Init();
110 
111  // Documentation inherited
112  public: virtual void Reset();
113 
114  // Documentation inherited
115  public: virtual void InitForThread();
116 
117  // Documentation inherited
118  public: virtual void UpdateCollision();
119 
120  // Documentation inherited
121  public: virtual void UpdatePhysics();
122 
123  // Documentation inherited
124  public: virtual void Fini();
125 
126  // Documentation inherited
127  public: virtual std::string GetType() const
128  { return "ode"; }
129 
130  // Documentation inherited
131  public: virtual LinkPtr CreateLink(ModelPtr _parent);
132 
133  // Documentation inherited
134  public: virtual CollisionPtr CreateCollision(
135  const std::string &_shapeType, LinkPtr _parent);
136 
137  // Documentation inherited
138  public: virtual ShapePtr CreateShape(const std::string &_shapeType,
139  CollisionPtr _collision);
140 
141  // Documentation inherited
142  public: virtual JointPtr CreateJoint(const std::string &_type,
143  ModelPtr _parent);
144 
145  // Documentation inherited
146  public: virtual void SetGravity(const gazebo::math::Vector3 &_gravity);
147 
148  // Documentation inherited
149  public: virtual void SetWorldCFM(double cfm);
150 
151  // Documentation inherited
152  public: virtual void SetWorldERP(double erp);
153 
154  // Documentation inherited
155  public: virtual void SetSORPGSPreconIters(unsigned int iters);
156 
157  // Documentation inherited
158  public: virtual void SetSORPGSIters(unsigned int iters);
159 
160  // Documentation inherited
161  public: virtual void SetSORPGSW(double w);
162 
163  // Documentation inherited
164  public: virtual void SetContactMaxCorrectingVel(double vel);
165 
166  // Documentation inherited
167  public: virtual void SetContactSurfaceLayer(double layer_depth);
168 
169  // Documentation inherited
170  public: virtual void SetMaxContacts(unsigned int max_contacts);
171 
172  // Documentation inherited
173  public: virtual double GetWorldCFM();
174 
175  // Documentation inherited
176  public: virtual double GetWorldERP();
177 
178  // Documentation inherited
179  public: virtual int GetSORPGSPreconIters();
180 
181  // Documentation inherited
182  public: virtual int GetSORPGSIters();
183 
184  // Documentation inherited
185  public: virtual double GetSORPGSW();
186 
187  // Documentation inherited
188  public: virtual double GetContactMaxCorrectingVel();
189 
190  // Documentation inherited
191  public: virtual double GetContactSurfaceLayer();
192 
193  // Documentation inherited
194  public: virtual unsigned int GetMaxContacts();
195 
196  // Documentation inherited
197  public: virtual void DebugPrint() const;
198 
199  // Documentation inherited
200  public: virtual void SetSeed(uint32_t _seed);
201 
203  public: virtual bool SetParam(const std::string &_key,
204  const boost::any &_value);
205 
207  public: virtual boost::any GetParam(const std::string &_key) const;
208 
211  public: dSpaceID GetSpaceId() const;
212 
215  public: dWorldID GetWorldId();
216 
220  public: static void ConvertMass(InertialPtr _interial, void *_odeMass);
221 
226  public: static void ConvertMass(void *_odeMass, InertialPtr _inertial);
227 
230  public: virtual std::string GetStepType() const;
231 
234  public: virtual void SetStepType(const std::string &_type);
235 
236 
241  public: void Collide(ODECollision *_collision1, ODECollision *_collision2,
242  dContactGeom *_contactCollisions);
243 
246  public: void ProcessJointFeedback(ODEJointFeedback *_feedback);
247 
248  protected: virtual void OnRequest(ConstRequestPtr &_msg);
249 
250  protected: virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg);
251 
256  private: static void CollisionCallback(void *_data, dGeomID _o1,
257  dGeomID _o2);
258 
259 
263  private: void AddTrimeshCollider(ODECollision *_collision1,
264  ODECollision *_collision2);
265 
269  private: void AddCollider(ODECollision *_collision1,
270  ODECollision *_collision2);
271 
273  private: dWorldID worldId;
274 
276  private: dSpaceID spaceId;
277 
279  private: dJointGroupID contactGroup;
280 
282  private: std::string stepType;
283 
285  private: std::vector<ODEJointFeedback*> jointFeedbacks;
286 
288  private: unsigned int jointFeedbackIndex;
289 
291  private: std::map<std::string, dSpaceID> spaces;
292 
294  private: std::vector< std::pair<ODECollision*, ODECollision*> > colliders;
295 
297  private: std::vector< std::pair<ODECollision*, ODECollision*> >
298  trimeshColliders;
299 
301  private: unsigned int collidersCount;
302 
304  private: unsigned int trimeshCollidersCount;
305 
307  private: dContactGeom contactCollisions[MAX_COLLIDE_RETURNS];
308 
310  private: int (*physicsStepFunc)(dxWorld*, dReal);
311 
313  private: int indices[MAX_CONTACT_JOINTS];
314 
316  private: unsigned int maxContacts;
317  };
318  }
319 }
320 #endif
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
ODEJointFeedback()
Definition: ODEPhysics.hh:44
virtual std::string GetType() const
Return the physics engine type (ode|bullet|dart|simbody).
Definition: ODEPhysics.hh:127
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
Constraint force mixing.
Definition: ODEPhysics.hh:67
Base class for all ODE collisions.
Definition: ODECollision.hh:39
boost::shared_ptr< Shape > ShapePtr
Definition: PhysicsTypes.hh:110
boost::shared_ptr< Inertial > InertialPtr
Definition: PhysicsTypes.hh:126
Base class for a physics engine.
Definition: PhysicsEngine.hh:40
Data structure for contact feedbacks.
Definition: ODEPhysics.hh:42
A contact between two collisions.
Definition: Contact.hh:54
Error reduction parameter.
Definition: ODEPhysics.hh:70
ODE physics engine.
Definition: ODEPhysics.hh:57
Minimum step size.
Definition: ODEPhysics.hh:91
Number of iterations.
Definition: ODEPhysics.hh:73
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:94
#define MAX_COLLIDE_RETURNS
Definition: Contact.hh:40
SOR over-relaxation parameter.
Definition: ODEPhysics.hh:79
Number of iterations.
Definition: ODEPhysics.hh:76
int count
Number of elements in feedbacks array.
Definition: ODEPhysics.hh:50
#define MAX_CONTACT_JOINTS
Definition: Contact.hh:41
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:78
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
#define NULL
Definition: CommonTypes.hh:30
Max correcting velocity.
Definition: ODEPhysics.hh:82
ODE wrapper forward declarations and typedefs.
Maximum number of contacts.
Definition: ODEPhysics.hh:88
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
Solve type.
Definition: ODEPhysics.hh:64
Contact * contact
Contact information.
Definition: ODEPhysics.hh:47
Surface layer depth.
Definition: ODEPhysics.hh:85
ODEParam
ODE Physics parameter types.
Definition: ODEPhysics.hh:61
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90