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 <string>
23 #include <utility>
24 
25 #include <boost/thread/thread.hpp>
26 
31 #include "gazebo/physics/Shape.hh"
32 #include "gazebo/gazebo_config.h"
33 #include "gazebo/util/system.hh"
34 
35 namespace gazebo
36 {
37  namespace physics
38  {
39  class ODEJointFeedback;
40  class ODEPhysicsPrivate;
41 
44  {
47  public: enum ODEParam
48  {
51 
54 
57 
60 
63 
65  SOR,
66 
69 
72 
75 
78 
82 
85 
87  WORLD_SOLVER_TYPE
88  };
89 
92  public: ODEPhysics(WorldPtr _world);
93 
95  public: virtual ~ODEPhysics();
96 
97  // Documentation inherited
98  public: virtual void Load(sdf::ElementPtr _sdf);
99 
100  // Documentation inherited
101  public: virtual void Init();
102 
103  // Documentation inherited
104  public: virtual void Reset();
105 
106  // Documentation inherited
107  public: virtual void InitForThread();
108 
109  // Documentation inherited
110  public: virtual void UpdateCollision();
111 
112  // Documentation inherited
113  public: virtual void UpdatePhysics();
114 
115  // Documentation inherited
116  public: virtual void Fini();
117 
118  // Documentation inherited
119  public: virtual std::string GetType() const
120  { return "ode"; }
121 
122  // Documentation inherited
123  public: virtual LinkPtr CreateLink(ModelPtr _parent);
124 
125  // Documentation inherited
126  public: virtual CollisionPtr CreateCollision(
127  const std::string &_shapeType, LinkPtr _parent);
128 
129  // Documentation inherited
130  public: virtual ShapePtr CreateShape(const std::string &_shapeType,
131  CollisionPtr _collision);
132 
133  // Documentation inherited
134  public: virtual JointPtr CreateJoint(const std::string &_type,
135  ModelPtr _parent);
136 
137  // Documentation inherited
138  public: virtual void SetGravity(const gazebo::math::Vector3 &_gravity);
139 
140  // Documentation inherited
141  public: virtual void SetWorldCFM(double cfm);
142 
143  // Documentation inherited
144  public: virtual void SetWorldERP(double erp);
145 
146  // Documentation inherited
147  public: virtual void SetSORPGSPreconIters(unsigned int iters);
148 
149  // Documentation inherited
150  public: virtual void SetSORPGSIters(unsigned int iters);
151 
152  // Documentation inherited
153  public: virtual void SetSORPGSW(double w);
154 
155  // Documentation inherited
156  public: virtual void SetContactMaxCorrectingVel(double vel);
157 
158  // Documentation inherited
159  public: virtual void SetContactSurfaceLayer(double layer_depth);
160 
163  public: virtual void SetFrictionModel(const std::string &_fricModel);
164 
167  public: virtual void
168  SetWorldStepSolverType(const std::string &_worldSolverType);
169 
170  // Documentation inherited
171  public: virtual void SetMaxContacts(unsigned int max_contacts);
172 
173  // Documentation inherited
174  public: virtual double GetWorldCFM();
175 
176  // Documentation inherited
177  public: virtual double GetWorldERP();
178 
179  // Documentation inherited
180  public: virtual int GetSORPGSPreconIters();
181 
182  // Documentation inherited
183  public: virtual int GetSORPGSIters();
184 
185  // Documentation inherited
186  public: virtual double GetSORPGSW();
187 
188  // Documentation inherited
189  public: virtual double GetContactMaxCorrectingVel();
190 
193  public: virtual std::string GetFrictionModel() const;
194 
197  public: virtual std::string GetWorldStepSolverType() const;
198 
199  // Documentation inherited
200  public: virtual double GetContactSurfaceLayer();
201 
202  // Documentation inherited
203  public: virtual unsigned int GetMaxContacts();
204 
205  // Documentation inherited
206  public: virtual void DebugPrint() const;
207 
208  // Documentation inherited
209  public: virtual void SetSeed(uint32_t _seed);
210 
212  public: virtual bool SetParam(const std::string &_key,
213  const boost::any &_value);
214 
216  public: virtual boost::any GetParam(const std::string &_key) const;
217 
219  public: virtual bool GetParam(const std::string &_key,
220  boost::any &_value) const;
221 
224  public: dSpaceID GetSpaceId() const;
225 
228  public: dWorldID GetWorldId();
229 
233  public: static void ConvertMass(InertialPtr _interial, void *_odeMass);
234 
239  public: static void ConvertMass(void *_odeMass, InertialPtr _inertial);
240 
245  public: static Friction_Model
246  ConvertFrictionModel(const std::string &_fricModel);
247 
252  public: static std::string
253  ConvertFrictionModel(const Friction_Model _fricModel);
254 
259  public: static std::string
260  ConvertWorldStepSolverType(const World_Solver_Type _solverType);
261 
266  public: static World_Solver_Type
267  ConvertWorldStepSolverType(const std::string &_solverType);
268 
271  public: virtual std::string GetStepType() const;
272 
275  public: virtual void SetStepType(const std::string &_type);
276 
277 
282  public: void Collide(ODECollision *_collision1, ODECollision *_collision2,
283  dContactGeom *_contactCollisions);
284 
287  public: void ProcessJointFeedback(ODEJointFeedback *_feedback);
288 
289  protected: virtual void OnRequest(ConstRequestPtr &_msg);
290 
291  protected: virtual void OnPhysicsMsg(ConstPhysicsPtr &_msg);
292 
297  private: static void CollisionCallback(void *_data, dGeomID _o1,
298  dGeomID _o2);
299 
300 
304  private: void AddTrimeshCollider(ODECollision *_collision1,
305  ODECollision *_collision2);
306 
310  private: void AddCollider(ODECollision *_collision1,
311  ODECollision *_collision2);
312 
315  private: ODEPhysicsPrivate *dataPtr;
316  };
317  }
318 }
319 #endif
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
Limit ratios of inertias of adjacent links (note that the corresponding SDF tag is "use_dynamic_moi_r...
Definition: ODEPhysics.hh:81
virtual std::string GetType() const
Return the physics engine type (ode|bullet|dart|simbody).
Definition: ODEPhysics.hh:119
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
Constraint force mixing.
Definition: ODEPhysics.hh:53
Base class for all ODE collisions.
Definition: ODECollision.hh:39
boost::shared_ptr< Shape > ShapePtr
Definition: PhysicsTypes.hh:116
boost::shared_ptr< Inertial > InertialPtr
Definition: PhysicsTypes.hh:132
Base class for a physics engine.
Definition: PhysicsEngine.hh:40
Data structure for contact feedbacks.
Definition: ODEPhysicsPrivate.hh:34
#define GZ_PHYSICS_ODE_VISIBLE
Definition: system.hh:343
Error reduction parameter.
Definition: ODEPhysics.hh:56
ODE physics engine.
Definition: ODEPhysics.hh:43
Minimum step size.
Definition: ODEPhysics.hh:77
Number of iterations.
Definition: ODEPhysics.hh:59
boost::shared_ptr< Collision > CollisionPtr
Definition: PhysicsTypes.hh:96
Definition: ODEPhysicsPrivate.hh:48
SOR over-relaxation parameter.
Definition: ODEPhysics.hh:65
Number of iterations.
Definition: ODEPhysics.hh:62
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:80
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
Max correcting velocity.
Definition: ODEPhysics.hh:68
ODE wrapper forward declarations and typedefs.
friction model
Definition: ODEPhysics.hh:84
Maximum number of contacts.
Definition: ODEPhysics.hh:74
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
Solve type.
Definition: ODEPhysics.hh:50
Surface layer depth.
Definition: ODEPhysics.hh:71
ODEParam
ODE Physics parameter types.
Definition: ODEPhysics.hh:47
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92