00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <uwsim/SceneBuilder.h>
00014
00015 #include <osg/Notify>
00016
00017 #include <string>
00018 #include <vector>
00019
00020 #include <uwsim/osgOceanScene.h>
00021 #include <uwsim/HUDCamera.h>
00022 #include <uwsim/VirtualRangeSensor.h>
00023 #include <uwsim/ROSInterface.h>
00024 #include <uwsim/UWSimUtils.h>
00025 #include <uwsim/TrajectoryVisualization.h>
00026
00027 using namespace std;
00028
00029 SceneBuilder::SceneBuilder()
00030 {
00031 int argc = 0;
00032 char **argv = NULL;
00033 arguments.reset(new osg::ArgumentParser(&argc, argv));
00034 }
00035
00036 SceneBuilder::SceneBuilder(int *argc, char **argv)
00037 {
00038 arguments.reset(new osg::ArgumentParser(argc, argv));
00039 }
00040
00041 SceneBuilder::SceneBuilder(boost::shared_ptr<osg::ArgumentParser> args)
00042 {
00043 arguments = args;
00044 }
00045
00046 bool SceneBuilder::loadScene(std::string xml_file)
00047 {
00048 ConfigFile config(xml_file);
00049
00050 return loadScene(config);
00051 }
00052
00055 bool SceneBuilder::loadScene(ConfigFile config)
00056 {
00057 float windx = config.windx, windy = config.windy;
00058 while (arguments->read("--windx", windx))
00059 ;
00060 while (arguments->read("--windy", windy))
00061 ;
00062 osg::Vec2f windDirection(windx, windy);
00063
00064 float windSpeed = config.windSpeed;
00065 while (arguments->read("--windSpeed", windSpeed))
00066 ;
00067
00068 float depth = config.depth;
00069
00070
00071 float reflectionDamping = config.reflectionDamping;
00072 while (arguments->read("--reflectionDamping", reflectionDamping))
00073 ;
00074
00075 float reswidth = config.resw, resheight = config.resh;
00076 while (arguments->read("--resw", reswidth))
00077 ;
00078 while (arguments->read("--resh", resheight))
00079 ;
00080
00081 float scale = config.waveScale;
00082 while (arguments->read("--waveScale", scale))
00083 ;
00084
00085 bool isChoppy = not config.isNotChoppy;
00086 while (arguments->read("--isNotChoppy"))
00087 isChoppy = false;
00088
00089 float choppyFactor = config.choppyFactor;
00090 while (arguments->read("--choppyFactor", choppyFactor))
00091 ;
00092 choppyFactor = -choppyFactor;
00093
00094 float crestFoamHeight = config.crestFoamHeight;
00095 while (arguments->read("--crestFoamHeight", crestFoamHeight))
00096 ;
00097
00098 double oceanSurfaceHeight = config.oceanSurfaceHeight;
00099 while (arguments->read("--oceanSurfaceHeight", oceanSurfaceHeight))
00100 ;
00101
00102 bool disableShaders = config.disableShaders;
00103 if (arguments->read("--disableShaders"))
00104 disableShaders = true;
00105
00106 bool disableTextures = false;
00107 if (arguments->read("--disableTextures"))
00108 disableTextures = true;
00109
00110 bool freeMotion = config.freeMotion;
00111 if (arguments->read("--freeMotion"))
00112 {
00113 freeMotion = true;
00114 }
00115
00116 osgOcean::ShaderManager::instance().enableShaders(!disableShaders);
00117
00118 root = new osg::Group;
00119
00120
00121 scene = new osgOceanScene(config.offsetp, config.offsetr, windDirection, windSpeed, depth, reflectionDamping, scale,
00122 isChoppy, choppyFactor, crestFoamHeight, false, "terrain");
00123
00124 if (disableShaders)
00125 {
00126
00127 scene->getOceanScene()->enableDistortion(false);
00128 scene->getOceanScene()->enableGlare(false);
00129 scene->getOceanScene()->enableUnderwaterDOF(false);
00130
00131
00132 scene->getOceanScene()->enableUnderwaterScattering(false);
00133
00134
00135 scene->getOceanScene()->enableReflections(false);
00136 scene->getOceanScene()->enableRefractions(false);
00137 scene->getOceanScene()->enableGodRays(false);
00138 scene->getOceanScene()->enableSilt(false);
00139 }
00140
00141 scene->getOceanScene()->setOceanSurfaceHeight(oceanSurfaceHeight);
00142 scene->getOceanScene()->setUnderwaterFog(config.fogDensity,
00143 osg::Vec4f(config.fogColor[0], config.fogColor[1], config.fogColor[2], 1));
00144 scene->getOceanScene()->setUnderwaterDiffuse(osg::Vec4f(config.color[0], config.color[1], config.color[2], 1));
00145 scene->getOceanScene()->setUnderwaterAttenuation(
00146 osg::Vec3f(config.attenuation[0], config.attenuation[1], config.attenuation[2]));
00147
00148
00149 int nvehicle = config.vehicles.size();
00150 for (int i = 0; i < nvehicle; i++)
00151 {
00152 Vehicle vehicle = config.vehicles.front();
00153 boost::shared_ptr < SimulatedIAUV > siauv(new SimulatedIAUV(this, vehicle));
00154 iauvFile.push_back(siauv);
00155 config.vehicles.pop_front();
00156
00157 scene->addObject(iauvFile[i]->baseTransform);
00158
00159 siauv->setVehiclePosition(vehicle.position[0], vehicle.position[1], vehicle.position[2], vehicle.orientation[0],
00160 vehicle.orientation[1], vehicle.orientation[2]);
00161
00162 for (int j = 0; j < vehicle.nlinks; j++)
00163 {
00164 NodeDataType * data = new NodeDataType(0);
00165 siauv->urdf->link[j]->setUserData(data);
00166 }
00167
00168 if (vehicle.jointValues.size() && siauv->urdf != NULL)
00169 {
00170 siauv->urdf->setJointPosition(vehicle.jointValues);
00171 }
00172
00173 }
00174
00175
00176 while (config.objects.size() > 0)
00177 {
00178 Object auxObject = config.objects.front();
00179
00180 osg::Matrixd wMb_m;
00181 wMb_m.makeRotate(
00182 osg::Quat(auxObject.orientation[0], osg::Vec3d(1, 0, 0), auxObject.orientation[1], osg::Vec3d(0, 1, 0),
00183 auxObject.orientation[2], osg::Vec3d(0, 0, 1)));
00184 wMb_m.setTrans(auxObject.position[0], auxObject.position[1], auxObject.position[2]);
00185
00186
00187
00188 osg::ref_ptr < osg::MatrixTransform > wMb = new osg::MatrixTransform(wMb_m);
00189 osg::Node *object = scene->addObject(wMb, auxObject.file, &auxObject);
00190 object->setName(auxObject.name);
00191
00192
00193 if (auxObject.name != "terrain")
00194 {
00195 NodeDataType * data = new NodeDataType(1, auxObject.position, auxObject.orientation);
00196 object->setUserData(data);
00197 }
00198 else
00199 {
00200 NodeDataType * data = new NodeDataType(0);
00201 object->setUserData(data);
00202 }
00203 objects.push_back(object);
00204 config.objects.pop_front();
00205 }
00206
00207
00208 root->addChild(scene->getScene());
00209
00210
00211
00212
00213 OSG_INFO << "Setting vehicle virtual cameras" << std::endl;
00214 for (int j = 0; j < nvehicle; j++)
00215 {
00216 for (unsigned int i = 0; i < iauvFile[j]->getNumCams(); i++)
00217 {
00218 iauvFile[j]->camview[i].textureCamera->addChild(scene->getScene());
00219 root->addChild(iauvFile[j]->camview[i].textureCamera);
00220
00221
00222 osg::Fog *fog = new osg::Fog();
00223 fog->setMode(osg::Fog::EXP2);
00224 fog->setFogCoordinateSource(osg::Fog::FRAGMENT_DEPTH);
00225 fog->setDensity(config.fogDensity);
00226 fog->setColor(osg::Vec4d(config.fogColor[0], config.fogColor[1], config.fogColor[2], 1));
00227 iauvFile[j]->camview[i].textureCamera->getOrCreateStateSet()->setAttributeAndModes(fog, osg::StateAttribute::ON);
00228 }
00229 }
00230
00231 OSG_INFO << "Setting interfaces with external software..." << std::endl;
00232 while (config.ROSInterfaces.size() > 0)
00233 {
00234 ROSInterfaceInfo rosInterface = config.ROSInterfaces.front();
00235
00236 boost::shared_ptr < ROSInterface > iface;
00237 if (rosInterface.type == ROSInterfaceInfo::ROSOdomToPAT)
00238 iface = boost::shared_ptr < ROSOdomToPAT
00239 > (new ROSOdomToPAT(root, rosInterface.topic, rosInterface.targetName));
00240
00241 if (rosInterface.type == ROSInterfaceInfo::ROSTwistToPAT)
00242 iface = boost::shared_ptr < ROSTwistToPAT
00243 > (new ROSTwistToPAT(root, rosInterface.topic, rosInterface.targetName));
00244
00245 if (rosInterface.type == ROSInterfaceInfo::PATToROSOdom)
00246 iface = boost::shared_ptr < PATToROSOdom
00247 > (new PATToROSOdom(root, rosInterface.targetName, rosInterface.topic, rosInterface.rate));
00248
00249 if (rosInterface.type == ROSInterfaceInfo::WorldToROSTF)
00250 {
00251 iface = boost::shared_ptr < WorldToROSTF
00252 > (new WorldToROSTF(root, iauvFile, objects, rosInterface.rootName, rosInterface.enableObjects, rosInterface.rate));
00253
00254 }
00255 if (rosInterface.type == ROSInterfaceInfo::ROSJointStateToArm
00256 || rosInterface.type == ROSInterfaceInfo::ArmToROSJointState)
00257 {
00258
00259 for (int j = 0; j < nvehicle; j++)
00260 {
00261 if (iauvFile[j]->name == rosInterface.targetName)
00262 {
00263 if (rosInterface.type == ROSInterfaceInfo::ROSJointStateToArm)
00264 iface = boost::shared_ptr < ROSJointStateToArm > (new ROSJointStateToArm(rosInterface.topic, iauvFile[j]));
00265 else
00266 iface = boost::shared_ptr < ArmToROSJointState
00267 > (new ArmToROSJointState(iauvFile[j].get(), rosInterface.topic, rosInterface.rate));
00268 }
00269 }
00270 }
00271
00272 if (rosInterface.type == ROSInterfaceInfo::VirtualCameraToROSImage)
00273
00274 for (int j = 0; j < nvehicle; j++)
00275 {
00276 for (unsigned int c = 0; c < iauvFile[j]->getNumCams(); c++)
00277 if (iauvFile[j]->camview[c].name == rosInterface.targetName)
00278 iface = boost::shared_ptr < VirtualCameraToROSImage
00279 > (new VirtualCameraToROSImage(&(iauvFile[j]->camview[c]), rosInterface.topic, rosInterface.infoTopic,
00280 rosInterface.rate, rosInterface.depth));
00281 }
00282 if (rosInterface.type == ROSInterfaceInfo::RangeImageSensorToROSImage)
00283
00284 for (int j = 0; j < nvehicle; j++)
00285 {
00286 for (unsigned int c = 0; c < iauvFile[j]->getNumCams(); c++)
00287 if (iauvFile[j]->camview[c].name == rosInterface.targetName)
00288 iface = boost::shared_ptr < VirtualCameraToROSImage
00289 > (new VirtualCameraToROSImage(&(iauvFile[j]->camview[c]), rosInterface.topic, rosInterface.infoTopic,
00290 rosInterface.rate, 1));
00291 }
00292 if (rosInterface.type == ROSInterfaceInfo::ROSImageToHUD)
00293 {
00294 boost::shared_ptr < HUDCamera
00295 > realcam(
00296 new HUDCamera(rosInterface.w, rosInterface.h, rosInterface.posx, rosInterface.posy, rosInterface.scale,
00297 rosInterface.blackWhite));
00298 iface = boost::shared_ptr < ROSImageToHUDCamera
00299 > (new ROSImageToHUDCamera(rosInterface.topic, rosInterface.infoTopic, realcam));
00300 realcams.push_back(realcam);
00301 }
00302
00303 if (rosInterface.type == ROSInterfaceInfo::RangeSensorToROSRange)
00304
00305 for (int j = 0; j < nvehicle; j++)
00306 {
00307 for (unsigned int c = 0; c < iauvFile[j]->getNumRangeSensors(); c++)
00308 if (iauvFile[j]->range_sensors[c].name == rosInterface.targetName)
00309 iface = boost::shared_ptr < RangeSensorToROSRange
00310 > (new RangeSensorToROSRange(&(iauvFile[j]->range_sensors[c]), rosInterface.topic, rosInterface.rate));
00311
00312 for (unsigned int c = 0; c < iauvFile[j]->getNumObjectPickers(); c++)
00313 if (iauvFile[j]->object_pickers[c].name == rosInterface.targetName)
00314 iface = boost::shared_ptr < RangeSensorToROSRange
00315 > (new RangeSensorToROSRange(&(iauvFile[j]->object_pickers[c]), rosInterface.topic, rosInterface.rate));
00316 }
00317
00318 if (rosInterface.type == ROSInterfaceInfo::ImuToROSImu)
00319
00320 for (int j = 0; j < nvehicle; j++)
00321 {
00322 for (unsigned int i = 0; i < iauvFile[j]->imus.size(); i++)
00323 if (iauvFile[j]->imus[i].name == rosInterface.targetName)
00324 iface = boost::shared_ptr < ImuToROSImu
00325 > (new ImuToROSImu(&(iauvFile[j]->imus[i]), rosInterface.topic, rosInterface.rate));
00326 }
00327
00328 if (rosInterface.type == ROSInterfaceInfo::PressureSensorToROS)
00329 for (int j = 0; j < nvehicle; j++)
00330 {
00331 for (unsigned int i = 0; i < iauvFile[j]->pressure_sensors.size(); i++)
00332 if (iauvFile[j]->pressure_sensors[i].name == rosInterface.targetName)
00333 iface = boost::shared_ptr < PressureSensorToROS
00334 > (new PressureSensorToROS(&(iauvFile[j]->pressure_sensors[i]), rosInterface.topic, rosInterface.rate));
00335 }
00336
00337 if (rosInterface.type == ROSInterfaceInfo::GPSSensorToROS)
00338 for (int j = 0; j < nvehicle; j++)
00339 {
00340 for (unsigned int i = 0; i < iauvFile[j]->gps_sensors.size(); i++)
00341 if (iauvFile[j]->gps_sensors[i].name == rosInterface.targetName)
00342 iface = boost::shared_ptr < GPSSensorToROS
00343 > (new GPSSensorToROS(&(iauvFile[j]->gps_sensors[i]), rosInterface.topic, rosInterface.rate));
00344 }
00345
00346 if (rosInterface.type == ROSInterfaceInfo::DVLSensorToROS)
00347 for (int j = 0; j < nvehicle; j++)
00348 {
00349 for (unsigned int i = 0; i < iauvFile[j]->dvl_sensors.size(); i++)
00350 if (iauvFile[j]->dvl_sensors[i].name == rosInterface.targetName)
00351 iface = boost::shared_ptr < DVLSensorToROS
00352 > (new DVLSensorToROS(&(iauvFile[j]->dvl_sensors[i]), rosInterface.topic, rosInterface.rate));
00353 }
00354 if (rosInterface.type == ROSInterfaceInfo::multibeamSensorToLaserScan)
00355 for (int j = 0; j < nvehicle; j++)
00356 {
00357 for (unsigned int i = 0; i < iauvFile[j]->multibeam_sensors.size(); i++)
00358 if (iauvFile[j]->multibeam_sensors[i].name == rosInterface.targetName)
00359 iface =
00360 boost::shared_ptr < MultibeamSensorToROS
00361 > (new MultibeamSensorToROS(&(iauvFile[j]->multibeam_sensors[i]), rosInterface.topic,
00362 rosInterface.rate));
00363 }
00364
00365 if (rosInterface.type == ROSInterfaceInfo::ROSPoseToPAT)
00366 iface = boost::shared_ptr < ROSPoseToPAT > (new ROSPoseToPAT(root, rosInterface.topic, rosInterface.targetName));
00367
00368 if (rosInterface.type == ROSInterfaceInfo::SimulatedDevice)
00369 {
00370 std::vector < boost::shared_ptr<ROSInterface> > ifaces = SimulatedDevices::getInterfaces(rosInterface, iauvFile);
00371 for (size_t i = 0; i < ifaces.size(); ++i)
00372 ROSInterfaces.push_back(ifaces[i]);
00373 }
00374
00375 if (iface)
00376 ROSInterfaces.push_back(iface);
00377 config.ROSInterfaces.pop_front();
00378 }
00379
00380
00381 while (config.trajectories.size() > 0)
00382 {
00383 ShowTrajectory trajectory = config.trajectories.front();
00384
00385 osg::ref_ptr<TrajectoryUpdateCallback> node_tracker = new TrajectoryUpdateCallback(trajectory.color, 0.02,trajectory.lineStyle, root);
00386 osg::Node * trackNode=findRN(trajectory.target,root);
00387 if(trackNode)
00388 trackNode->setUpdateCallback(node_tracker);
00389 else
00390 OSG_FATAL << "Scene Builder: "<<trajectory.target<<" trajectory target not found, please check your XML."<<std::endl;
00391
00392 config.trajectories.pop_front();
00393 }
00394
00395 return true;
00396 }
00397
00398 SceneBuilder::~SceneBuilder()
00399 {
00400
00401
00402
00403
00404
00405 }
00406