All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Macros Groups Pages
ODEPhysics.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 _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 
91  MIN_STEP_SIZE
92  };
93 
96  public: ODEPhysics(WorldPtr _world);
97 
99  public: virtual ~ODEPhysics();
100 
101  // Documentation inherited
102  public: virtual void Load(sdf::ElementPtr _sdf);
103 
104  // Documentation inherited
105  public: virtual void Init();
106 
107  // Documentation inherited
108  public: virtual void Reset();
109 
110  // Documentation inherited
111  public: virtual void InitForThread();
112 
113  // Documentation inherited
114  public: virtual void UpdateCollision();
115 
116  // Documentation inherited
117  public: virtual void UpdatePhysics();
118 
119  // Documentation inherited
120  public: virtual void Fini();
121 
122  // Documentation inherited
123  public: virtual std::string GetType() const
124  { return "ode"; }
125 
126  // Documentation inherited
127  public: virtual LinkPtr CreateLink(ModelPtr _parent);
128 
129  // Documentation inherited
130  public: virtual CollisionPtr CreateCollision(
131  const std::string &_shapeType, LinkPtr _parent);
132 
133  // Documentation inherited
134  public: virtual ShapePtr CreateShape(const std::string &_shapeType,
135  CollisionPtr _collision);
136 
137  // Documentation inherited
138  public: virtual JointPtr CreateJoint(const std::string &_type,
139  ModelPtr _parent);
140 
141  // Documentation inherited
142  public: virtual void SetGravity(const gazebo::math::Vector3 &_gravity);
143 
144  // Documentation inherited
145  public: virtual void SetWorldCFM(double cfm);
146 
147  // Documentation inherited
148  public: virtual void SetWorldERP(double erp);
149 
150  // Documentation inherited
151  public: virtual void SetSORPGSPreconIters(unsigned int iters);
152 
153  // Documentation inherited
154  public: virtual void SetSORPGSIters(unsigned int iters);
155 
156  // Documentation inherited
157  public: virtual void SetSORPGSW(double w);
158 
159  // Documentation inherited
160  public: virtual void SetContactMaxCorrectingVel(double vel);
161 
162  // Documentation inherited
163  public: virtual void SetContactSurfaceLayer(double layer_depth);
164 
165  // Documentation inherited
166  public: virtual void SetMaxContacts(unsigned int max_contacts);
167 
168  // Documentation inherited
169  public: virtual double GetWorldCFM();
170 
171  // Documentation inherited
172  public: virtual double GetWorldERP();
173 
174  // Documentation inherited
175  public: virtual int GetSORPGSPreconIters();
176 
177  // Documentation inherited
178  public: virtual int GetSORPGSIters();
179 
180  // Documentation inherited
181  public: virtual double GetSORPGSW();
182 
183  // Documentation inherited
184  public: virtual double GetContactMaxCorrectingVel();
185 
186  // Documentation inherited
187  public: virtual double GetContactSurfaceLayer();
188 
189  // Documentation inherited
190  public: virtual unsigned int GetMaxContacts();
191 
192  // Documentation inherited
193  public: virtual void DebugPrint() const;
194 
195  // Documentation inherited
196  public: virtual void SetSeed(uint32_t _seed);
197 
199  public: virtual bool SetParam(const std::string &_key,
200  const boost::any &_value);
201 
203  public: virtual boost::any GetParam(const std::string &_key) const;
204 
207  public: dSpaceID GetSpaceId() const;
208 
211  public: dWorldID GetWorldId();
212 
216  public: static void ConvertMass(InertialPtr _interial, void *_odeMass);
217 
222  public: static void ConvertMass(void *_odeMass, InertialPtr _inertial);
223 
226  public: virtual std::string GetStepType() const;
227 
230  public: virtual void SetStepType(const std::string &_type);
231 
232 
237  public: void Collide(ODECollision *_collision1, ODECollision *_collision2,
238  dContactGeom *_contactCollisions);
239 
242  public: void ProcessJointFeedback(ODEJointFeedback *_feedback);
243 
244  protected: virtual void OnRequest(ConstRequestPtr &_msg);
245 
246  protected: virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg);
247 
252  private: static void CollisionCallback(void *_data, dGeomID _o1,
253  dGeomID _o2);
254 
255 
259  private: void AddTrimeshCollider(ODECollision *_collision1,
260  ODECollision *_collision2);
261 
265  private: void AddCollider(ODECollision *_collision1,
266  ODECollision *_collision2);
267 
269  private: dWorldID worldId;
270 
272  private: dSpaceID spaceId;
273 
275  private: dJointGroupID contactGroup;
276 
278  private: std::string stepType;
279 
281  private: std::vector<ODEJointFeedback*> jointFeedbacks;
282 
284  private: unsigned int jointFeedbackIndex;
285 
287  private: std::map<std::string, dSpaceID> spaces;
288 
290  private: std::vector< std::pair<ODECollision*, ODECollision*> > colliders;
291 
293  private: std::vector< std::pair<ODECollision*, ODECollision*> >
294  trimeshColliders;
295 
297  private: unsigned int collidersCount;
298 
300  private: unsigned int trimeshCollidersCount;
301 
303  private: dContactGeom contactCollisions[MAX_COLLIDE_RETURNS];
304 
306  private: int (*physicsStepFunc)(dxWorld*, dReal);
307 
309  private: int indices[MAX_CONTACT_JOINTS];
310 
312  private: unsigned int maxContacts;
313  };
314  }
315 }
316 #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:123
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
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