SimulatedIAUV.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/SceneBuilder.h>
00014 #include <uwsim/osgOceanScene.h>
00015 #include <uwsim/SimulatorConfig.h>
00016 #include <uwsim/SimulatedIAUV.h>
00017 #include <uwsim/URDFRobot.h>
00018 #include <osg/MatrixTransform>
00019 #include <osg/PositionAttitudeTransform>
00020 
00022 /*
00023  class LightUpdateCallback:public osg::NodeCallback {
00024  osg::Transform *trackNode;     ///< Node that the light must track
00025 
00026  public:
00027  LightUpdateCallback(osg::Transform *trackNode)
00028  {this->trackNode=trackNode;}
00029 
00030  void operator () (osg::Node *node, osg::NodeVisitor *nv) {
00031  //update light position to track the node
00032  osg::LightSource *ls=dynamic_cast<osg::LightSource*>(node);
00033  osg::Light *l=ls->getLight();
00034  osg::PositionAttitudeTransform *pat=trackNode->asPositionAttitudeTransform();
00035  osg::Vec3d pos=pat->getPosition();
00036  l->setPosition( osg::Vec4f(pos.x(),pos.y(),pos.z()-0.5, 1.f) );
00037 
00038  //call to standard callback
00039  osg::NodeCallback::operator()(node,nv);
00040  }
00041  };
00042  */
00043 
00044 /*
00045  SimulatedIAUV::SimulatedIAUV(osgOcean::OceanScene *oscene, arm_t armtype) {
00046  vehicle=new SimulatedVehicle(oscene, "GIRONA500/girona500.osg");
00047 
00048  if (armtype==PA10)
00049  arm=new SimulatedPA10(oscene);
00050  else if (armtype==ARM5)
00051  arm=new SimulatedArmFromURDF5(oscene);
00052 
00053  baseTransform=NULL;
00054  if(vehicle->baseTransform!=NULL && arm->baseTransform!=NULL) {
00055  baseTransform=vehicle->baseTransform;
00056  baseTransform->addChild(arm->baseTransform);
00057 
00058  //Vehicle frame to Arm base frame transform
00059  osg::Matrix m=arm->baseTransform->getMatrix();
00060  if (armtype==PA10) {
00061  m.makeRotate(M_PI,1,0,0);
00062  } else if (armtype==ARM5) {
00063  }
00064  arm->baseTransform->setMatrix(m);
00065  }
00066  camview=NULL;
00067 
00068  //Set-up a lamp attached to the vehicle
00069  osg::Light *_light=new osg::Light;
00070  _light->setLightNum(1);
00071  _light->setAmbient( osg::Vec4d(1.0f, 1.0f, 1.0f, 1.0f ));
00072  _light->setDiffuse( osg::Vec4d( 1.0, 1.0, 1.0, 1.0 ) );
00073  _light->setSpecular(osg::Vec4d( 0.1f, 0.1f, 0.1f, 1.0f ) );
00074  _light->setDirection(osg::Vec3d(0.0, 0.0, -5.0));
00075  _light->setSpotCutoff(40.0);
00076  _light->setSpotExponent(10.0);
00077 
00078  lightSource = new osg::LightSource;
00079  lightSource->setLight(_light);
00080  lightSource->setLocalStateSetModes(osg::StateAttribute::ON);
00081  lightSource->setUpdateCallback(new LightUpdateCallback(baseTransform));
00082  }
00083  */
00084 
00085 SimulatedIAUV::SimulatedIAUV(SceneBuilder *oscene, Vehicle vehicleChars) :
00086     urdf(new URDFRobot(oscene->scene->getOceanScene(), vehicleChars))
00087 {
00088   name = vehicleChars.name;
00089   baseTransform = new osg::MatrixTransform;
00090 
00091   if (urdf->baseTransform != NULL /* && arm->baseTransform!=NULL*/)
00092   {
00093     baseTransform->addChild(urdf->baseTransform);
00094     baseTransform->setName(vehicleChars.name);
00095   }
00096   scale=osg::Vec3d(vehicleChars.scale[0],vehicleChars.scale[1],vehicleChars.scale[2]);
00097 
00098   //Add virtual  cameras in config file
00099   while (vehicleChars.Vcams.size() > 0)
00100   {
00101     Vcam vcam = vehicleChars.Vcams.front();
00102     OSG_INFO << "Adding a virtual camera " << vcam.name << "..." << std::endl;
00103     vehicleChars.Vcams.pop_front();
00104     //Camera frame given wrt vehicle origin frame.
00105     //Remember that in opengl/osg, the camera frame is a right-handed system with Z going backwards (opposite to the viewing direction) and Y up.
00106     osg::ref_ptr < osg::Transform > vMc = (osg::Transform*)new osg::PositionAttitudeTransform;
00107     vMc->asPositionAttitudeTransform()->setPosition(osg::Vec3d(vcam.position[0], vcam.position[1], vcam.position[2]));
00108     vMc->asPositionAttitudeTransform()->setAttitude(
00109         osg::Quat(vcam.orientation[0], osg::Vec3d(1, 0, 0), vcam.orientation[1], osg::Vec3d(0, 1, 0),
00110                   vcam.orientation[2], osg::Vec3d(0, 0, 1)));
00111     urdf->link[vcam.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMc);
00112     camview.push_back(
00113         VirtualCamera(oscene->root, vcam.name, vcam.linkName, vMc, vcam.resw, vcam.resh, vcam.baseLine, vcam.frameId,
00114                       vcam.fov,oscene,vcam.std,vcam.parameters.get(), 0, vcam.bw));
00115     if (vcam.showpath)
00116       camview[camview.size() - 1].showPath(vcam.showpath);
00117     OSG_INFO << "Done adding a virtual camera..." << std::endl;
00118   }
00119 
00120   //Add virtual range cameras in config file
00121   while (vehicleChars.VRangecams.size() > 0)
00122   {
00123     Vcam vcam = vehicleChars.VRangecams.front();
00124     OSG_INFO << "Adding a virtual camera " << vcam.name << "..." << std::endl;
00125     vehicleChars.VRangecams.pop_front();
00126     //Camera frame given wrt vehicle origin frame.
00127     //Remember that in opengl/osg, the camera frame is a right-handed system with Z going backwards (opposite to the viewing direction) and Y up.
00128     osg::ref_ptr < osg::Transform > vMc = (osg::Transform*)new osg::PositionAttitudeTransform;
00129     vMc->asPositionAttitudeTransform()->setPosition(osg::Vec3d(vcam.position[0], vcam.position[1], vcam.position[2]));
00130     vMc->asPositionAttitudeTransform()->setAttitude(
00131         osg::Quat(vcam.orientation[0], osg::Vec3d(1, 0, 0), vcam.orientation[1], osg::Vec3d(0, 1, 0),
00132                   vcam.orientation[2], osg::Vec3d(0, 0, 1)));
00133     urdf->link[vcam.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMc);
00134     camview.push_back(
00135         VirtualCamera(oscene->root, vcam.name, vcam.linkName, vMc, vcam.resw, vcam.resh, vcam.baseLine, vcam.frameId,
00136                       vcam.fov,NULL,0,vcam.parameters.get(), 1, 0));
00137     if (vcam.showpath)
00138       camview[camview.size() - 1].showPath(vcam.showpath);
00139     OSG_INFO << "Done adding a virtual camera..." << std::endl;
00140   }
00141 
00142   // Adding Structured light projector
00143   while (vehicleChars.sls_projectors.size() > 0)
00144   {
00145     OSG_INFO << "Adding a structured light projector..." << std::endl;
00146     slProjector slp;
00147     slp = vehicleChars.sls_projectors.front();
00148     vehicleChars.sls_projectors.pop_front();
00149     osg::ref_ptr < osg::Transform > vMp = (osg::Transform*)new osg::PositionAttitudeTransform;
00150     vMp->asPositionAttitudeTransform()->setPosition(osg::Vec3d(slp.position[0], slp.position[1], slp.position[2]));
00151     vMp->asPositionAttitudeTransform()->setAttitude(
00152         osg::Quat(slp.orientation[0], osg::Vec3d(1, 0, 0), slp.orientation[1], osg::Vec3d(0, 1, 0), slp.orientation[2],
00153                   osg::Vec3d(0, 0, 1)));
00154     urdf->link[slp.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMp);
00155     //camview.push_back(VirtualCamera(oscene->root, "slp_camera", vMp, 512, 512,slp.fov,102.4));
00156     sls_projectors.push_back(VirtualSLSProjector(slp.name, slp.linkName, oscene->root, //maybe oscene->scene->localizedWorld ?
00157                                                  vMp, slp.image_name, slp.fov, (slp.laser) ? true : false));
00158     camview.push_back(sls_projectors.back().camera);
00159     OSG_INFO << "Done adding a structured light projector..." << std::endl;
00160   }
00161 
00162   //Adding range sensors
00163   while (vehicleChars.range_sensors.size() > 0)
00164   {
00165     OSG_INFO << "Adding a virtual range sensor..." << std::endl;
00166     rangeSensor rs;
00167     rs = vehicleChars.range_sensors.front();
00168     vehicleChars.range_sensors.pop_front();
00169     osg::ref_ptr < osg::Transform > vMr = (osg::Transform*)new osg::PositionAttitudeTransform;
00170     vMr->asPositionAttitudeTransform()->setPosition(osg::Vec3d(rs.position[0], rs.position[1], rs.position[2]));
00171     vMr->asPositionAttitudeTransform()->setAttitude(
00172         osg::Quat(rs.orientation[0], osg::Vec3d(1, 0, 0), rs.orientation[1], osg::Vec3d(0, 1, 0), rs.orientation[2],
00173                   osg::Vec3d(0, 0, 1)));
00174     urdf->link[rs.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMr);
00175     range_sensors.push_back(
00176         VirtualRangeSensor(rs.name, rs.linkName, oscene->scene->localizedWorld, vMr, rs.range, (rs.visible) ? true : false,
00177         oscene->scene->getOceanScene()->getARMask()));
00178     OSG_INFO << "Done adding a virtual range sensor..." << std::endl;
00179   }
00180 
00181   //Adding imus
00182   while (vehicleChars.imus.size() > 0)
00183   {
00184     OSG_INFO << "Adding an IMU..." << std::endl;
00185     Imu imu;
00186     imu = vehicleChars.imus.front();
00187     vehicleChars.imus.pop_front();
00188     osg::ref_ptr < osg::Transform > vMi = (osg::Transform*)new osg::PositionAttitudeTransform;
00189     vMi->asPositionAttitudeTransform()->setPosition(osg::Vec3d(imu.position[0], imu.position[1], imu.position[2]));
00190     vMi->asPositionAttitudeTransform()->setAttitude(
00191         osg::Quat(imu.orientation[0], osg::Vec3d(1, 0, 0), imu.orientation[1], osg::Vec3d(0, 1, 0), imu.orientation[2],
00192                   osg::Vec3d(0, 0, 1)));
00193     urdf->link[imu.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMi);
00194     imus.push_back(InertialMeasurementUnit(imu.name, imu.linkName, vMi, oscene->scene->localizedWorld->getMatrix(), imu.std));
00195     OSG_INFO << "Done adding an IMU..." << std::endl;
00196   }
00197 
00198   //Adding pressure sensors
00199   while (vehicleChars.pressure_sensors.size() > 0)
00200   {
00201     OSG_INFO << "Adding a pressure sensor..." << std::endl;
00202     XMLPressureSensor ps;
00203     ps = vehicleChars.pressure_sensors.front();
00204     vehicleChars.pressure_sensors.pop_front();
00205     osg::ref_ptr < osg::Transform > vMs = (osg::Transform*)new osg::PositionAttitudeTransform;
00206     vMs->asPositionAttitudeTransform()->setPosition(osg::Vec3d(ps.position[0], ps.position[1], ps.position[2]));
00207     vMs->asPositionAttitudeTransform()->setAttitude(
00208         osg::Quat(ps.orientation[0], osg::Vec3d(1, 0, 0), ps.orientation[1], osg::Vec3d(0, 1, 0), ps.orientation[2],
00209                   osg::Vec3d(0, 0, 1)));
00210     urdf->link[ps.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMs);
00211     pressure_sensors.push_back(PressureSensor(ps.name, ps.linkName, vMs, oscene->scene->localizedWorld->getMatrix(), ps.std));
00212     OSG_INFO << "Done adding an Pressure Sensor..." << std::endl;
00213   }
00214 
00215   //Adding GPS sensors
00216   while (vehicleChars.gps_sensors.size() > 0)
00217   {
00218     OSG_INFO << "Adding a gps sensor..." << std::endl;
00219     XMLGPSSensor ps;
00220     ps = vehicleChars.gps_sensors.front();
00221     vehicleChars.gps_sensors.pop_front();
00222     osg::ref_ptr < osg::Transform > vMs = (osg::Transform*)new osg::PositionAttitudeTransform;
00223     vMs->asPositionAttitudeTransform()->setPosition(osg::Vec3d(ps.position[0], ps.position[1], ps.position[2]));
00224     vMs->asPositionAttitudeTransform()->setAttitude(
00225         osg::Quat(ps.orientation[0], osg::Vec3d(1, 0, 0), ps.orientation[1], osg::Vec3d(0, 1, 0), ps.orientation[2],
00226                   osg::Vec3d(0, 0, 1)));
00227     urdf->link[ps.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMs);
00228     gps_sensors.push_back(GPSSensor(oscene->scene, ps.name, ps.linkName , vMs, oscene->scene->localizedWorld->getMatrix(), ps.std));
00229     OSG_INFO << "Done adding an GPS Sensor..." << std::endl;
00230   }
00231 
00232   //Adding dvl sensors
00233   while (vehicleChars.dvl_sensors.size() > 0)
00234   {
00235     OSG_INFO << "Adding a dvl sensor..." << std::endl;
00236     XMLDVLSensor ps;
00237     ps = vehicleChars.dvl_sensors.front();
00238     vehicleChars.dvl_sensors.pop_front();
00239     osg::ref_ptr < osg::Transform > vMs = (osg::Transform*)new osg::PositionAttitudeTransform;
00240     vMs->asPositionAttitudeTransform()->setPosition(osg::Vec3d(ps.position[0], ps.position[1], ps.position[2]));
00241     vMs->asPositionAttitudeTransform()->setAttitude(
00242         osg::Quat(ps.orientation[0], osg::Vec3d(1, 0, 0), ps.orientation[1], osg::Vec3d(0, 1, 0), ps.orientation[2],
00243                   osg::Vec3d(0, 0, 1)));
00244     urdf->link[ps.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMs);
00245     dvl_sensors.push_back(DVLSensor(ps.name, ps.linkName, vMs, oscene->scene->localizedWorld->getMatrix(), ps.std));
00246     OSG_INFO << "Done adding an DVL Sensor..." << std::endl;
00247   }
00248 
00249   //Adding Multibeam sensors
00250   while (vehicleChars.multibeam_sensors.size() > 0)
00251   {
00252     OSG_INFO << "Adding a Multibeam sensor..." << std::endl;
00253     XMLMultibeamSensor MB;
00254     MB = vehicleChars.multibeam_sensors.front();
00255     vehicleChars.multibeam_sensors.pop_front();
00256     osg::ref_ptr < osg::Transform > vMs = (osg::Transform*)new osg::PositionAttitudeTransform;
00257     vMs->asPositionAttitudeTransform()->setPosition(osg::Vec3d(MB.position[0], MB.position[1], MB.position[2]));
00258     vMs->asPositionAttitudeTransform()->setAttitude(
00259         osg::Quat(MB.orientation[0], osg::Vec3d(1, 0, 0), MB.orientation[1], osg::Vec3d(0, 1, 0), MB.orientation[2],
00260                   osg::Vec3d(0, 0, 1)));
00261     urdf->link[MB.link]->getParent(0)->getParent(0)->asGroup()->addChild(vMs);
00262     unsigned int mask;
00263     if(MB.underwaterParticles)
00264       mask=oscene->scene->getOceanScene()->getARMask();
00265     else
00266       mask=oscene->scene->getOceanScene()->getNormalSceneMask(); //Normal Scene mask should be enough for range sensor
00267     MultibeamSensor mb = MultibeamSensor(oscene->root, MB.name, MB.linkName, vMs, MB.initAngle, MB.finalAngle, MB.angleIncr,
00268                                          MB.range,mask,MB.visible,mask);
00269     multibeam_sensors.push_back(mb);
00270     for(unsigned int i=0;i<mb.nCams;i++)
00271       camview.push_back(mb.vcams[i]);
00272     OSG_INFO << "Done adding a Multibeam Sensor..." << std::endl;
00273   }
00274 
00275   //Adding object pickers
00276   while (vehicleChars.object_pickers.size() > 0)
00277   {
00278     OSG_INFO << "Adding an object picker..." << std::endl;
00279     rangeSensor rs;
00280     rs = vehicleChars.object_pickers.front();
00281     vehicleChars.object_pickers.pop_front();
00282     osg::ref_ptr < osg::Transform > vMr = (osg::Transform*)new osg::PositionAttitudeTransform;
00283     vMr->asPositionAttitudeTransform()->setPosition(osg::Vec3d(rs.position[0], rs.position[1], rs.position[2]));
00284     vMr->asPositionAttitudeTransform()->setAttitude(
00285         osg::Quat(rs.orientation[0], osg::Vec3d(1, 0, 0), rs.orientation[1], osg::Vec3d(0, 1, 0), rs.orientation[2],
00286                   osg::Vec3d(0, 0, 1)));
00287     vMr->setName("ObjectPickerNode");
00288     urdf->link[rs.link]->asGroup()->addChild(vMr);
00289     object_pickers.push_back(ObjectPicker(rs.name, oscene->scene->localizedWorld, vMr, rs.range, true, urdf,
00290         oscene->scene->getOceanScene()->getARMask()));
00291     OSG_INFO << "Done adding an object picker..." << std::endl;
00292   }
00293 
00294   devices.reset(new SimulatedDevices());
00295   devices->applyConfig(this, vehicleChars, oscene);
00296 
00297   //Set-up a lamp attached to the vehicle: TODO
00298   /*
00299    osg::Light *_light=new osg::Light;
00300    _light->setLightNum(1);
00301    _light->setAmbient( osg::Vec4d(1.0f, 1.0f, 1.0f, 1.0f ));
00302    _light->setDiffuse( osg::Vec4d( 1.0, 1.0, 1.0, 1.0 ) );
00303    _light->setSpecular(osg::Vec4d( 0.1f, 0.1f, 0.1f, 1.0f ) );
00304    _light->setDirection(osg::Vec3d(0.0, 0.0, -5.0));
00305    _light->setSpotCutoff(40.0);
00306    _light->setSpotExponent(10.0);
00307 
00308    lightSource = new osg::LightSource;
00309    lightSource->setLight(_light);
00310    lightSource->setLocalStateSetModes(osg::StateAttribute::ON);
00311    lightSource->setUpdateCallback(new LightUpdateCallback(baseTransform));
00312    */
00313 }
00314 
00315 /*
00316  void SimulatedIAUV::setVirtualCamera(std::string name, osg::Transform* transform, int width, int height) {
00317  //Set I-AUV virtual camera
00318 
00319  baseTransform->asGroup()->addChild(transform);
00320 
00321  if (camview==NULL)
00322  camview=new VirtualCamera(name, transform, width, height);
00323  }
00324  */
00325 
00327 void SimulatedIAUV::setVehiclePosition(double x, double y, double z, double roll, double pitch, double yaw)
00328 {
00329   osg::Matrixd S, T, Rx, Ry, Rz, transform;
00330   T.makeTranslate(x, y, z);
00331   Rx.makeRotate(roll, 1, 0, 0);
00332   Ry.makeRotate(pitch, 0, 1, 0);
00333   Rz.makeRotate(yaw, 0, 0, 1);
00334   S.makeScale(scale);
00335   transform = S * Rz * Ry * Rx * T;
00336   setVehiclePosition(transform);
00337 }
00338 
00339 void SimulatedIAUV::setVehiclePosition(osg::Matrixd m)
00340 {
00341   baseTransform->setMatrix(m);
00342 }
00343 


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