osgOceanScene.cpp
Go to the documentation of this file.
00001 /*
00002  * This source file is part of the osgOcean library
00003  *
00004  * Copyright (C) 2009 Kim Bale
00005  * Copyright (C) 2009 The University of Hull, UK
00006  *
00007  * This program is free software; you can redistribute it and/or modify it under
00008  * the terms of the GNU Lesser General Public License as published by the Free Software
00009  * Foundation; either version 3 of the License, or (at your option) any later
00010  * version.
00011 
00012  * This program is distributed in the hope that it will be useful, but WITHOUT
00013  * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
00014  * FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.
00015  * http://www.gnu.org/copyleft/lesser.txt.
00016  *
00017  * Adapted to UWSim by Mario Prats
00018  */
00019 
00020 #include <uwsim/SimulatorConfig.h>
00021 #include <uwsim/osgOceanScene.h>
00022 #include <uwsim/UWSimUtils.h>
00023 
00024 #include <osg/Shape>
00025 #include <osg/ShapeDrawable>
00026 #include <osg/PositionAttitudeTransform>
00027 #include <osg/Program>
00028 #include <osg/LightSource>
00029 #include <uwsim/ConfigXMLParser.h>
00030 
00031 #include <osgOcean/ShaderManager>
00032 
00033 // ----------------------------------------------------
00034 //               Camera Track Callback
00035 // ----------------------------------------------------
00036 
00037 class CameraTrackCallback : public osg::NodeCallback
00038 {
00039 public:
00040   virtual void operator()(osg::Node* node, osg::NodeVisitor* nv)
00041   {
00042     if (nv->getVisitorType() == osg::NodeVisitor::CULL_VISITOR)
00043     {
00044       osgUtil::CullVisitor* cv = static_cast<osgUtil::CullVisitor*>(nv);
00045       osg::Vec3f centre, up, eye;
00046       // get MAIN camera eye,centre,up
00047       cv->getRenderStage()->getCamera()->getViewMatrixAsLookAt(eye, centre, up);
00048       // update position
00049       osg::MatrixTransform* mt = static_cast<osg::MatrixTransform*>(node);
00050       mt->setMatrix(osg::Matrix::translate(eye.x(), eye.y(), mt->getMatrix().getTrans().z()));
00051     }
00052 
00053     traverse(node, nv);
00054   }
00055 };
00056 
00057 // ----------------------------------------------------
00058 //                       Scene 
00059 // ----------------------------------------------------
00060 
00061 osgOceanScene::osgOceanScene(double offsetp[3], double offsetr[3], const osg::Vec2f& windDirection, float windSpeed,
00062                              float depth, float reflectionDamping, float scale, bool isChoppy, float choppyFactor,
00063                              float crestFoamHeight, bool useVBO, const std::string& terrain_shader_basename)
00064 {
00065   _sceneType = CLEAR;
00066   _useVBO = useVBO;
00067 
00068   _cubemapDirs.push_back("sky_clear");
00069   _cubemapDirs.push_back("sky_dusk");
00070   _cubemapDirs.push_back("sky_fair_cloudy");
00071 
00072   _fogColors.push_back(intColor(199, 226, 255));
00073   _fogColors.push_back(intColor(244, 228, 179));
00074   _fogColors.push_back(intColor(172, 224, 251));
00075 
00076   _waterFogColors.push_back(intColor(27, 57, 109));
00077   _waterFogColors.push_back(intColor(44, 69, 106));
00078   _waterFogColors.push_back(intColor(84, 135, 172));
00079 
00080   _underwaterAttenuations.push_back(osg::Vec3f(0.015f, 0.0075f, 0.005f));
00081   _underwaterAttenuations.push_back(osg::Vec3f(0.015f, 0.0075f, 0.005f));
00082   _underwaterAttenuations.push_back(osg::Vec3f(0.008f, 0.003f, 0.002f));
00083 
00084   _underwaterDiffuse.push_back(intColor(27, 57, 109));
00085   _underwaterDiffuse.push_back(intColor(44, 69, 106));
00086   _underwaterDiffuse.push_back(intColor(84, 135, 172));
00087 
00088   _lightColors.push_back(intColor(105, 138, 174));
00089   _lightColors.push_back(intColor(105, 138, 174));
00090   _lightColors.push_back(intColor(105, 138, 174));
00091 
00092   _sunPositions.push_back(osg::Vec3f(326.573, 1212.99, 1275.19));
00093   _sunPositions.push_back(osg::Vec3f(520.f, 1900.f, 550.f));
00094   _sunPositions.push_back(osg::Vec3f(-1056.89f, -771.886f, 1221.18f));
00095 
00096   _sunDiffuse.push_back(intColor(191, 191, 191));
00097   _sunDiffuse.push_back(intColor(251, 251, 161));
00098   _sunDiffuse.push_back(intColor(191, 191, 191));
00099 
00100   build(offsetp, offsetr, windDirection, windSpeed, depth, reflectionDamping, scale, isChoppy, choppyFactor,
00101         crestFoamHeight, _useVBO, terrain_shader_basename);
00102 }
00103 
00104 void osgOceanScene::build(double offsetp[3], double offsetr[3], const osg::Vec2f& windDirection, float windSpeed,
00105                           float depth, float reflectionDamping, float waveScale, bool isChoppy, float choppyFactor,
00106                           float crestFoamHeight, bool useVBO, const std::string& terrain_shader_basename)
00107 {
00108   {
00109     ScopedTimer buildSceneTimer("Building scene... \n", osg::notify(osg::NOTICE));
00110 
00111     _scene = new osg::Group;
00112 
00113     {
00114       ScopedTimer cubemapTimer("  . Loading cubemaps: ", osg::notify(osg::NOTICE));
00115       _cubemap = loadCubeMapTextures(_cubemapDirs[_sceneType]);
00116     }
00117 
00118     // Set up surface
00119     {
00120       ScopedTimer oceanSurfaceTimer("  . Generating ocean surface: ", osg::notify(osg::NOTICE));
00121 
00122       if (useVBO)
00123       {
00124         _FFToceanSurface = new osgOcean::FFTOceanSurfaceVBO(64, 256, 17, windDirection, windSpeed, depth,
00125                                                             reflectionDamping, waveScale, isChoppy, choppyFactor, 10.f,
00126                                                             256);
00127       }
00128       else
00129       {
00130         _FFToceanSurface = new osgOcean::FFTOceanSurface(64, 256, 17, windDirection, windSpeed, depth,
00131                                                          reflectionDamping, waveScale, isChoppy, choppyFactor, 10.f,
00132                                                          256);
00133       }
00134 
00135       _FFToceanSurface->setEnvironmentMap(_cubemap.get());
00136       _FFToceanSurface->setFoamBottomHeight(2.2f);
00137       _FFToceanSurface->setFoamTopHeight(3.0f);
00138       _FFToceanSurface->enableCrestFoam(true);
00139       _FFToceanSurface->setLightColor(_lightColors[_sceneType]);
00140       // Make the ocean surface track with the main camera position, giving the illusion
00141       // of an endless ocean surface.
00142       _FFToceanSurface->enableEndlessOcean(true);
00143     }
00144 
00145     // Set up ocean scene, add surface
00146     {
00147       ScopedTimer oceanSceneTimer("  . Creating ocean scene: ", osg::notify(osg::NOTICE));
00148       osg::Vec3f sunDir = -_sunPositions[_sceneType];
00149       sunDir.normalize();
00150 
00151       _oceanScene = new osgOcean::OceanScene(_FFToceanSurface.get());
00152       _oceanScene->setLightID(0);
00153       _oceanScene->enableReflections(true);
00154       _oceanScene->enableRefractions(true);
00155       _oceanScene->enableHeightmap(true);
00156 
00157       // Set the size of _oceanCylinder which follows the camera underwater.
00158       // This cylinder prevents the clear from being visible past the far plane
00159       // instead it will be the fog color.
00160       // The size of the cylinder should be changed according the size of the ocean surface.
00161       _oceanScene->setCylinderSize(1900.f, 4000.f);
00162 
00163       _oceanScene->setAboveWaterFog(0.0012f, _fogColors[_sceneType]);
00164       _oceanScene->setUnderwaterFog(0.002f, _waterFogColors[_sceneType]);
00165       _oceanScene->setUnderwaterDiffuse(_underwaterDiffuse[_sceneType]);
00166       _oceanScene->setUnderwaterAttenuation(_underwaterAttenuations[_sceneType]);
00167 
00168       _oceanScene->setSunDirection(sunDir);
00169       _oceanScene->enableGodRays(true);
00170       _oceanScene->enableSilt(true);
00171       _oceanScene->enableUnderwaterDOF(false);
00172       _oceanScene->enableUnderwaterScattering(true);
00173       _oceanScene->enableDistortion(true);
00174       _oceanScene->enableGlare(false);
00175       _oceanScene->setGlareAttenuation(0.8f);
00176 
00177       // create sky dome and add to ocean scene
00178       // set masks so it appears in reflected scene and normal scene
00179       _skyDome = new SkyDome(1900.f, 16, 16, _cubemap.get());
00180       _skyDome->setNodeMask(
00181           _oceanScene->getReflectedSceneMask() | _oceanScene->getNormalSceneMask()
00182               | _oceanScene->getRefractedSceneMask());
00183 
00184       // add a pat to track the camera
00185       osg::MatrixTransform* transform = new osg::MatrixTransform;
00186       transform->setDataVariance(osg::Object::DYNAMIC);
00187       transform->setMatrix(osg::Matrixf::translate(osg::Vec3f(0.f, 0.f, 0.f)));
00188       transform->setCullCallback(new CameraTrackCallback);
00189 
00190       transform->addChild(_skyDome.get());
00191 
00192       _oceanScene->addChild(transform);
00193 
00194       {
00195         // Create and add fake texture for use with nodes without any texture
00196         // since the OceanScene default scene shader assumes that texture unit
00197         // 0 is used as a base texture map.
00198         osg::Image * image = new osg::Image;
00199         image->allocateImage(1, 1, 1, GL_RGBA, GL_UNSIGNED_BYTE);
00200         *(osg::Vec4ub*)image->data() = osg::Vec4ub(0xFF, 0xFF, 0xFF, 0xFF);
00201 
00202         osg::Texture2D* fakeTex = new osg::Texture2D(image);
00203         fakeTex->setWrap(osg::Texture2D::WRAP_S, osg::Texture2D::REPEAT);
00204         fakeTex->setWrap(osg::Texture2D::WRAP_T, osg::Texture2D::REPEAT);
00205         fakeTex->setFilter(osg::Texture2D::MIN_FILTER, osg::Texture2D::NEAREST);
00206         fakeTex->setFilter(osg::Texture2D::MAG_FILTER, osg::Texture2D::NEAREST);
00207 
00208         osg::StateSet* stateset = _oceanScene->getOrCreateStateSet();
00209         stateset->setTextureAttribute(0, fakeTex, osg::StateAttribute::ON);
00210         stateset->setTextureMode(0, GL_TEXTURE_1D, osg::StateAttribute::OFF);
00211         stateset->setTextureMode(0, GL_TEXTURE_2D, osg::StateAttribute::ON);
00212         stateset->setTextureMode(0, GL_TEXTURE_3D, osg::StateAttribute::OFF);
00213       }
00214 
00215     }
00216 
00217     {
00218       ScopedTimer lightingTimer("  . Setting up lighting: ", osg::notify(osg::NOTICE));
00219       osg::LightSource* lightSource = new osg::LightSource;
00220       lightSource->setNodeMask(lightSource->getNodeMask() & ~CAST_SHADOW & ~RECEIVE_SHADOW);
00221       lightSource->setLocalStateSetModes();
00222 
00223       _light = lightSource->getLight();
00224       _light->setLightNum(0);
00225       _light->setAmbient(osg::Vec4d(0.3f, 0.3f, 0.3f, 1.0f));
00226       _light->setDiffuse(_sunDiffuse[_sceneType]);
00227       _light->setSpecular(osg::Vec4d(0.1f, 0.1f, 0.1f, 1.0f));
00228 #ifdef POINT_LIGHT
00229       _light->setPosition( osg::Vec4f(_sunPositions[_sceneType], 1.f) ); // point light
00230 #else
00231       osg::Vec3f direction(_sunPositions[_sceneType]);
00232       direction.normalize();
00233       _light->setPosition(osg::Vec4f(direction, 0.0)); // directional light
00234 #endif
00235 
00236       _scene->addChild(lightSource);
00237       _scene->addChild(_oceanScene.get());
00238       //_scene->addChild( sunDebug(_sunPositions[CLOUDY]) );
00239     }
00240     {
00241       //Add a coordinate transform relating the simulated world frame with respect to an arbitrary localized world
00242       ScopedTimer lightingTimer("  . Setting localized world: ", osg::notify(osg::ALWAYS));
00243       osg::Matrixd wMl;
00244       wMl.makeRotate(offsetr[0], 1, 0, 0);
00245       wMl.preMultRotate(osg::Quat(offsetr[1], osg::Vec3d(0, 1, 0)));
00246       wMl.preMultRotate(osg::Quat(offsetr[2], osg::Vec3d(0, 0, 1)));
00247       wMl.setTrans(offsetp[0], offsetp[1], offsetp[2]);
00248       localizedWorld = new osg::MatrixTransform(wMl);
00249       localizedWorld->setName("localizedWorld");
00250       //add frame to localized world
00251       osg::ref_ptr < osg::Node > axis = UWSimGeometry::createSwitchableFrame();
00252       localizedWorld->asGroup()->addChild(axis);
00253 
00254       _oceanScene->addChild(localizedWorld);
00255     }
00256 
00257     osg::notify(osg::NOTICE) << "complete.\nTime Taken: ";
00258   }
00259 }
00260 
00261 void osgOceanScene::changeScene(SCENE_TYPE type)
00262 {
00263   _sceneType = type;
00264 
00265   _cubemap = loadCubeMapTextures(_cubemapDirs[_sceneType]);
00266   _skyDome->setCubeMap(_cubemap.get());
00267 
00268   _FFToceanSurface->setEnvironmentMap(_cubemap.get());
00269   _FFToceanSurface->setLightColor(_lightColors[type]);
00270 
00271   _oceanScene->setAboveWaterFog(0.0012f, _fogColors[_sceneType]);
00272   _oceanScene->setUnderwaterFog(0.002f, _waterFogColors[_sceneType]);
00273   _oceanScene->setUnderwaterDiffuse(_underwaterDiffuse[_sceneType]);
00274   _oceanScene->setUnderwaterAttenuation(_underwaterAttenuations[_sceneType]);
00275 
00276   osg::Vec3f sunDir = -_sunPositions[_sceneType];
00277   sunDir.normalize();
00278 
00279   _oceanScene->setSunDirection(sunDir);
00280 
00281 #ifdef POINT_LIGHT
00282   _light->setPosition( osg::Vec4f(_sunPositions[_sceneType], 1.f) );
00283 #else
00284   _light->setPosition(osg::Vec4f(-sunDir, 0.f));
00285 #endif
00286   _light->setDiffuse(_sunDiffuse[_sceneType]);
00287 
00288   if (_islandSwitch.valid())
00289   {
00290     if (_sceneType == CLEAR || _sceneType == CLOUDY)
00291       _islandSwitch->setAllChildrenOn();
00292     else
00293       _islandSwitch->setAllChildrenOff();
00294   }
00295 }
00296 
00297 #define USE_CUSTOM_SHADER
00298 
00299 // Load the islands model
00300 // Here we attach a custom shader to the model.
00301 // This shader overrides the default shader applied by OceanScene but uses uniforms applied by OceanScene.
00302 // The custom shader is needed to add multi-texturing and bump mapping to the terrain.
00303 osg::Node* osgOceanScene::loadIslands(const std::string& terrain_shader_basename)
00304 {
00305   osgDB::Registry::instance()->getDataFilePathList().push_back("resources/island");
00306   const std::string filename = "islands.ive";
00307   osg::ref_ptr < osg::Node > island = osgDB::readNodeFile(filename);
00308 
00309   if (!island.valid())
00310   {
00311     osg::notify(osg::WARN) << "Could not find: " << filename << std::endl;
00312     return NULL;
00313   }
00314 
00315 #ifdef USE_CUSTOM_SHADER
00316   const std::string terrain_vertex = terrain_shader_basename + ".vert";
00317   const std::string terrain_fragment = terrain_shader_basename + ".frag";
00318 
00319   osg::Program* program = osgOcean::ShaderManager::instance().createProgram("terrain", terrain_vertex, terrain_fragment,
00320                                                                             "", "");
00321   if (program)
00322     program->addBindAttribLocation("aTangent", 6);
00323 
00324 #endif
00325   island->setNodeMask(
00326       _oceanScene->getNormalSceneMask() | _oceanScene->getReflectedSceneMask() | _oceanScene->getRefractedSceneMask()
00327           | _oceanScene->getHeightmapMask() | RECEIVE_SHADOW);
00328   island->getStateSet()->addUniform(new osg::Uniform("uTextureMap", 0));
00329 
00330 #ifdef USE_CUSTOM_SHADER
00331   island->getOrCreateStateSet()->setAttributeAndModes(program, osg::StateAttribute::ON);
00332   island->getStateSet()->addUniform(new osg::Uniform("uOverlayMap", 1));
00333   island->getStateSet()->addUniform(new osg::Uniform("uNormalMap", 2));
00334 #endif
00335   osg::PositionAttitudeTransform* islandpat = new osg::PositionAttitudeTransform;
00336   islandpat->setPosition(osg::Vec3f(-island->getBound().center() + osg::Vec3f(0.0, 0.0, -15.f)));
00337   islandpat->setScale(osg::Vec3f(4.f, 4.f, 3.f));
00338   islandpat->addChild(island.get());
00339 
00340   return islandpat;
00341 }
00342 
00343 osg::ref_ptr<osg::TextureCubeMap> osgOceanScene::loadCubeMapTextures(const std::string& dir)
00344 {
00345   enum
00346   {
00347     POS_X, NEG_X, POS_Y, NEG_Y, POS_Z, NEG_Z
00348   };
00349 
00350   std::string filenames[6];
00351 
00352   const std::string SIMULATOR_DATA_PATH = std::string(getenv("HOME")) + "/.uwsim/data";
00353 
00354   filenames[POS_X] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/east.png";
00355   filenames[NEG_X] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/west.png";
00356   filenames[POS_Z] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/north.png";
00357   filenames[NEG_Z] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/south.png";
00358   filenames[POS_Y] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/down.png";
00359   filenames[NEG_Y] = std::string(SIMULATOR_DATA_PATH) + "/textures/" + dir + "/up.png";
00360 
00361   osg::ref_ptr < osg::TextureCubeMap > cubeMap = new osg::TextureCubeMap;
00362   cubeMap->setInternalFormat(GL_RGBA);
00363 
00364   cubeMap->setFilter(osg::Texture::MIN_FILTER, osg::Texture::LINEAR_MIPMAP_LINEAR);
00365   cubeMap->setFilter(osg::Texture::MAG_FILTER, osg::Texture::LINEAR);
00366   cubeMap->setWrap(osg::Texture::WRAP_S, osg::Texture::CLAMP_TO_EDGE);
00367   cubeMap->setWrap(osg::Texture::WRAP_T, osg::Texture::CLAMP_TO_EDGE);
00368 
00369   cubeMap->setImage(osg::TextureCubeMap::NEGATIVE_X, osgDB::readImageFile(filenames[NEG_X]));
00370   cubeMap->setImage(osg::TextureCubeMap::POSITIVE_X, osgDB::readImageFile(filenames[POS_X]));
00371   cubeMap->setImage(osg::TextureCubeMap::NEGATIVE_Y, osgDB::readImageFile(filenames[NEG_Y]));
00372   cubeMap->setImage(osg::TextureCubeMap::POSITIVE_Y, osgDB::readImageFile(filenames[POS_Y]));
00373   cubeMap->setImage(osg::TextureCubeMap::NEGATIVE_Z, osgDB::readImageFile(filenames[NEG_Z]));
00374   cubeMap->setImage(osg::TextureCubeMap::POSITIVE_Z, osgDB::readImageFile(filenames[POS_Z]));
00375 
00376   return cubeMap;
00377 }
00378 
00379 osg::Geode* osgOceanScene::sunDebug(const osg::Vec3f& position)
00380 {
00381   osg::ShapeDrawable* sphereDraw = new osg::ShapeDrawable(new osg::Sphere(position, 15.f));
00382   sphereDraw->setColor(osg::Vec4f(1.f, 0.f, 0.f, 1.f));
00383 
00384   osg::Geode* sphereGeode = new osg::Geode;
00385   sphereGeode->addDrawable(sphereDraw);
00386 
00387   return sphereGeode;
00388 }
00389 
00390 osg::Node* osgOceanScene::addObject(osg::Transform *transform, std::string filename, Object *o)
00391 {
00392   const std::string SIMULATOR_DATA_PATH = std::string(getenv("HOME")) + "/.uwsim/data";
00393   osgDB::Registry::instance()->getDataFilePathList().push_back(std::string(SIMULATOR_DATA_PATH));
00394   osgDB::Registry::instance()->getDataFilePathList().push_back(
00395       std::string(SIMULATOR_DATA_PATH) + std::string("/objects"));
00396   osgDB::Registry::instance()->getDataFilePathList().push_back(
00397       std::string(SIMULATOR_DATA_PATH) + std::string("/terrain"));
00398   osgDB::Registry::instance()->getDataFilePathList().push_back(
00399       std::string(UWSIM_ROOT_PATH) + std::string("/data/shaders"));
00400   osg::ref_ptr < osg::Node > object = osgDB::readNodeFile(filename);
00401 
00402   if (!object.valid())
00403   {
00404     OSG_FATAL << "Error: could not find: " << filename << std::endl;
00405     return NULL;
00406   }
00407   else
00408   {
00409 
00410     static const char model_vertex[] = "default_scene.vert";
00411     static const char model_fragment[] = "default_scene.frag";
00412 
00413     osg::Program* program = osgOcean::ShaderManager::instance().createProgram("object_shader", model_vertex,
00414                                                                               model_fragment, "", "");
00415     program->addBindAttribLocation("aTangent", 6);
00416 
00417     object->getOrCreateStateSet()->setAttributeAndModes(program, osg::StateAttribute::ON);
00418     object->getStateSet()->addUniform(new osg::Uniform("uOverlayMap", 1));
00419     object->getStateSet()->addUniform(new osg::Uniform("uNormalMap", 2));
00420     object->getStateSet()->addUniform(new osg::Uniform("SLStex", 3));
00421     object->getStateSet()->addUniform(new osg::Uniform("SLStex2", 4));
00422     object->setNodeMask(
00423         _oceanScene->getNormalSceneMask() | _oceanScene->getReflectedSceneMask()
00424             | _oceanScene->getRefractedSceneMask());
00425 
00426     osg::Matrix linkBase;
00427     linkBase.makeIdentity();
00428     linkBase.preMultRotate(osg::Quat(o->offsetr[0], osg::Vec3d(1, 0, 0)));
00429     linkBase.preMultRotate(osg::Quat(o->offsetr[1], osg::Vec3d(0, 1, 0)));
00430     linkBase.preMultRotate(osg::Quat(o->offsetr[2], osg::Vec3d(0, 0, 1)));
00431     linkBase.preMultTranslate(osg::Vec3d(-o->offsetp[0], -o->offsetp[1], -o->offsetp[2]));
00432 
00433     osg::ref_ptr < osg::MatrixTransform > linkBaseTransform = new osg::MatrixTransform(linkBase);
00434     //If object is not a group, create a group and make it son of it
00435     if (object->asGroup() == NULL)
00436     {
00437       osg::ref_ptr < osg::Node > aux = object;
00438       object = (osg::ref_ptr<osg::Node>)new osg::Group();
00439       object->asGroup()->addChild(aux.get());
00440     }
00441     linkBaseTransform->addChild(object);
00442 
00443     osg::Matrix linkPost;
00444     linkBase.invert(linkPost);
00445 
00446     osg::ref_ptr < osg::MatrixTransform > linkPostTransform = new osg::MatrixTransform(linkPost);
00447 
00448     object->asGroup()->addChild(linkPostTransform);
00449 
00450     transform->addChild(linkBaseTransform);
00451     localizedWorld->addChild(transform);
00452     return object.get();
00453   }
00454 }
00455 
00456 void osgOceanScene::addObject(osg::Transform *transform)
00457 {
00458   if (transform != NULL)
00459     localizedWorld->addChild(transform);
00460 }


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