BulletPhysics.h
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2013 University of Jaume-I.
00003  * All rights reserved. This program and the accompanying materials
00004  * are made available under the terms of the GNU Public License v3.0
00005  * which accompanies this distribution, and is available at
00006  * http://www.gnu.org/licenses/gpl.html
00007  * 
00008  * Contributors:
00009  *     Mario Prats
00010  *     Javier Perez
00011  */
00012 
00013 #ifndef BULLETPHYSICS_H_
00014 #define BULLETPHYSICS_H_
00015 
00016 #include "SimulatorConfig.h"
00017 #include "UWSimUtils.h"
00018 
00019 #include <osgbDynamics/MotionState.h>
00020 #include <osgbCollision/CollisionShapes.h>
00021 #include <osgbCollision/Utils.h>
00022 
00023 #include <btBulletDynamicsCommon.h>
00024 #include <iostream>
00025 
00026 #include <osgOcean/OceanScene>
00027 
00028 //#include <osgbCollision/GLDebugDrawer.h>
00029 
00030 #define UWSIM_DEFAULT_GRAVITY   btVector3(0,0,-1)
00031 
00032 // Define filter groups
00033 enum CollisionTypes
00034 {
00035   COL_NOTHING = 0x00000000, COL_OBJECTS = 0x00000001, COL_VEHICLE = 0x00000010, COL_EVERYTHING = 0x11111111,
00036 };
00037 
00038 /*class NodeDataType : public osg::Referenced{
00039  public:
00040  NodeDataType(btRigidBody * rigidBody,int catcha){ catchable=catcha; rb=rigidBody;};
00041  int catchable;
00042  btRigidBody * rb;
00043 
00044  };*/
00045 
00046 class CollisionDataType : public osg::Referenced
00047 {
00048 public:
00049   CollisionDataType(std::string nam, std::string vehName, int isVehi)
00050   {
00051     vehicleName = vehName;
00052     name = nam;
00053     isVehicle = isVehi;
00054   }
00055   ;
00056   std::string getObjectName()
00057   {
00058     if (isVehicle)
00059       return vehicleName;
00060     else
00061       return name;
00062   }
00063   ;
00064   std::string name, vehicleName;
00065   int isVehicle;
00066 
00067 };
00068 
00069 //Adds tick callback manager which will do all stuff needed in pretick callback
00070 void preTickCallback(btDynamicsWorld *world, btScalar timeStep);
00071 
00072 //Adds tick callback manager which will do all stuff needed in posttick callback
00073 void postTickCallback(btDynamicsWorld *world, btScalar timeStep);
00074 
00075 class BulletPhysics : public osg::Referenced
00076 {
00077 
00078 public:
00079   typedef enum
00080   {
00081     SHAPE_BOX, SHAPE_SPHERE, SHAPE_TRIMESH, SHAPE_COMPOUND_TRIMESH, SHAPE_COMPOUND_BOX, SHAPE_COMPOUND_CYLINDER
00082   } collisionShapeType_t;
00083 
00084   btDiscreteDynamicsWorld * dynamicsWorld;
00085   //osgbCollision::GLDebugDrawer debugDrawer;
00086 
00087   BulletPhysics(PhysicsConfig physicsConfig, osgOcean::OceanTechnique* oceanSurf);
00088 
00089   void setGravity(btVector3 g)
00090   {
00091     dynamicsWorld->setGravity(g);
00092   }
00093   btRigidBody* addObject(osg::MatrixTransform *root, osg::Node *node, CollisionDataType * data,
00094                          boost::shared_ptr<PhysicProperties> pp, osg::Node * colShape = NULL);
00095 
00096   void stepSimulation(btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep);
00097   void printManifolds();
00098 
00099   int getNumCollisions();
00100 
00101   btRigidBody* copyObject(btRigidBody * copied);
00102   int physicsStep;
00103 
00104   btPersistentManifold * getCollision(int i);
00105 
00106   ~BulletPhysics()
00107   {
00108   }
00109   ;
00110 
00111   //This class stores information related to different sources that need to be called in internal tick callbacks.
00112   //To know force sensors.
00113   class TickCallbackManager
00114   {
00115     private:
00116       //Force sensor structures;
00117       struct ForceSensorcbInfo
00118       {
00119         btRigidBody * copy, * target;
00120         btVector3 linInitial, angInitial,linFinal, angFinal;
00121       };
00122       std::vector<ForceSensorcbInfo> forceSensors;
00123     
00124       void preTickForceSensors();
00125       void postTickForceSensors();
00126     public:
00127 
00128       int substep; //Tracks number of substep;
00129 
00130       TickCallbackManager(){};
00131       int addForceSensor(btRigidBody * copy, btRigidBody * target);
00132       void getForceSensorSpeed(int forceSensor, double linSpeed[3],double angSpeed[3]);
00133       void physicsInternalPreProcessCallback(btScalar timeStep);
00134       void physicsInternalPostProcessCallback(btScalar timeStep);
00135   };
00136 
00137 
00138   TickCallbackManager * callbackManager;
00139 
00140 private:
00141   btDefaultCollisionConfiguration * collisionConfiguration;
00142   btCollisionDispatcher * dispatcher;
00143   btConstraintSolver * solver;
00144   btBroadphaseInterface * inter;
00145 
00146   osgOcean::OceanTechnique* oceanSurface;
00147 
00148   void cleanManifolds();
00149   btCollisionShape* GetCSFromOSG(osg::Node * node, collisionShapeType_t ctype);
00150 
00151 };
00152 
00153 
00154 #endif  
00155 


uwsim
Author(s): Mario Prats , Javier Perez
autogenerated on Fri Aug 28 2015 13:28:58