PhysicsBuilder.cpp
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 #include <uwsim/PhysicsBuilder.h>
00014 
00015 PhysicsBuilder::PhysicsBuilder(SceneBuilder * scene_builder, ConfigFile config)
00016 {
00017   loadPhysics(scene_builder, config);
00018 }
00019 
00020 void PhysicsBuilder::loadPhysics(SceneBuilder * scene_builder, ConfigFile config)
00021 {
00022 
00023   physics = new BulletPhysics(config.gravity, scene_builder->scene->getOceanSurface(), config.physicsWater);
00024   OSG_INFO << "Loading Physics" << std::endl;
00025 
00026   //Add physics to vehicles
00027   for (unsigned int i = 0; i < scene_builder->iauvFile.size(); i++)
00028   {
00029     for (unsigned int j = 0; j < scene_builder->iauvFile[i]->urdf->link.size(); j++)
00030     {
00031       osg::Node * link = scene_builder->iauvFile[i]->urdf->link[j];
00032       osg::Node * cs = NULL;
00033       btRigidBody* rigidBody;
00034       boost::shared_ptr<PhysicProperties> pp;
00035       pp.reset(new PhysicProperties);
00036       pp->init();
00037       pp->isKinematic = 1;
00038       pp->csType = "compound box";
00039       pp->mass=0;
00040       //Look for config vehicle, to search for physic properties.
00041       for (std::list<Vehicle>::iterator cfgVehicle = config.vehicles.begin(); cfgVehicle != config.vehicles.end();
00042           cfgVehicle++)
00043         if (cfgVehicle->name == scene_builder->iauvFile[i]->name)
00044           for (unsigned int part = 0; part < cfgVehicle->links.size(); part++)
00045             if (cfgVehicle->links[part].name == link->getName()) //Config vehicle found!
00046             {
00047               if(cfgVehicle->links[part].cs) //Add collisionShape if available
00048               {
00049                 cs = UWSimGeometry::loadGeometry(cfgVehicle->links[part].cs);
00050                 if (!cs)
00051                   std::cerr << "Collision shape couldn't load, using visual to create physics" << std::endl;
00052               }
00053 
00054               if(cfgVehicle->links[part].mass > 0)  //If mass is set in config add it.
00055                 pp->mass=cfgVehicle->links[part].mass;
00056             }
00057 
00058       CollisionDataType * colData = new CollisionDataType(link->getName(), scene_builder->iauvFile[i]->name, 1);
00059       rigidBody = physics->addObject(NULL, link, colData, pp, cs);
00060 
00061       //Update visual node data with physics properties
00062       osg::ref_ptr < NodeDataType > data = dynamic_cast<NodeDataType*>(link->getUserData());
00063       data->rigidBody = rigidBody;
00064       link->setUserData(data);
00065 
00066       //TODO: Add node data type correctly(hand actuator).
00067       //NodeDataType * data= new NodeDataType(floorbody,0);
00068       //link->setUserData(data);
00069     }
00070     scene_builder->iauvFile[i]->urdf->physics = physics;
00071 
00072     assert(scene_builder->iauvFile[i]->devices.get() != NULL);
00073     //apply physics to devices
00074     for (unsigned int j = 0; j < scene_builder->iauvFile[i]->devices->all.size(); j++)
00075       scene_builder->iauvFile[i]->devices->all[j]->applyPhysics(physics);
00076   }
00077 
00078   //Add physics to objects  
00079   for (unsigned int i = 0; i < scene_builder->objects.size(); i++)
00080   {
00081     //create Matrix Transform to use it on physics
00082     osg::Matrix mat;
00083     mat.makeIdentity();
00084     osg::MatrixTransform * mt = new osg::MatrixTransform();
00085     osg::Group * parent = scene_builder->objects[i]->getParent(0);
00086     mt->addChild(scene_builder->objects[i]);
00087     parent->removeChild(scene_builder->objects[i]);
00088     parent->addChild(mt);
00089 
00090     //NodeDataType * data;
00091     CollisionDataType * colData = new CollisionDataType(scene_builder->objects[i]->getName(), " ", 0);
00092 
00093     //Search for object in config, and look for physic properties
00094     boost::shared_ptr < PhysicProperties > pp;
00095     for (std::list<Object>::iterator j = config.objects.begin(); j != config.objects.end(); j++)
00096     {
00097       if (j->name == scene_builder->objects[i]->getName())
00098       {
00099         pp = j->physicProperties;
00100       }
00101 
00102     }
00103 
00104     //Check if object has a collisionShape defined
00105     osg::Node * cs = NULL;
00106     if (pp && pp->cs != "")
00107       cs = UWSimGeometry::retrieveResource(pp->cs);
00108 
00109     btRigidBody* rigidBody;
00110 
00111     //Objects  objects with simple shapes will be added with water physics and rest with physics.
00112     if (config.physicsWater.enable && (pp->csType == "box" || pp->csType == "sphere"))
00113     {
00114       rigidBody = physics->addFloatingObject(mt, scene_builder->objects[i], colData, pp, cs);
00115     }
00116     else
00117     {
00118       rigidBody = physics->addObject(mt, scene_builder->objects[i], colData, pp, cs);
00119     }
00120     //wMb->setUserData(data); 
00121 
00122     //store physiscs in object's data
00123     osg::ref_ptr < NodeDataType > data = dynamic_cast<NodeDataType*>(scene_builder->objects[i]->getUserData());
00124     data->rigidBody = rigidBody;
00125     scene_builder->objects[i]->setUserData(data);
00126   }
00127 
00128   //Add ROSPhysInterfaces
00129   while (config.ROSPhysInterfaces.size() > 0)
00130   {
00131     ROSInterfaceInfo rosInterface = config.ROSPhysInterfaces.front();
00132 
00133     boost::shared_ptr < ROSInterface > iface;
00134 
00135     if (rosInterface.type == ROSInterfaceInfo::contactSensorToROS)
00136       iface = boost::shared_ptr < contactSensorToROS
00137           > (new contactSensorToROS(scene_builder->root, physics, rosInterface.targetName, rosInterface.topic,
00138                                     rosInterface.rate));
00139 
00140     scene_builder->ROSInterfaces.push_back(iface);
00141     config.ROSPhysInterfaces.pop_front();
00142 
00143   }
00144 
00145   OSG_INFO << "Physics Loaded!" << std::endl;
00146 
00147 }
00148 


uwsim
Author(s): Mario Prats
autogenerated on Mon Oct 6 2014 08:24:07