Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #include <ros/ros.h>
00014
00015 #include <string>
00016 #include <vector>
00017 #include <stdlib.h>
00018
00019 #include <uwsim/ConfigXMLParser.h>
00020 #include <uwsim/SceneBuilder.h>
00021 #include <uwsim/ViewBuilder.h>
00022 #include <uwsim/PhysicsBuilder.h>
00023 #include "osgbCollision/GLDebugDrawer.h"
00024 #include <uwsim/UWSimUtils.h>
00025
00026 using namespace std;
00027
00028
00029
00030 int main(int argc, char *argv[])
00031 {
00032
00033
00034 boost::shared_ptr<osg::ArgumentParser> arguments(new osg::ArgumentParser(&argc, argv));
00035 arguments->getApplicationUsage()->setApplicationName(arguments->getApplicationName());
00036 arguments->getApplicationUsage()->setDescription(arguments->getApplicationName() + " is using osgOcean.");
00037 arguments->getApplicationUsage()->setCommandLineUsage(arguments->getApplicationName() + " [options] ...");
00038 arguments->getApplicationUsage()->addCommandLineOption("--windx <x>", "Wind X direction.");
00039 arguments->getApplicationUsage()->addCommandLineOption("--windy <y>", "Wind Y direction.");
00040 arguments->getApplicationUsage()->addCommandLineOption("--windSpeed <speed>", "Wind speed.");
00041 arguments->getApplicationUsage()->addCommandLineOption("--isNotChoppy", "Set the waves not choppy.");
00042 arguments->getApplicationUsage()->addCommandLineOption("--choppyFactor <factor>", "How choppy the waves are.");
00043 arguments->getApplicationUsage()->addCommandLineOption(
00044 "--crestFoamHeight <height>", "How high the waves need to be before foam forms on the crest.");
00045 arguments->getApplicationUsage()->addCommandLineOption("--oceanSurfaceHeight <z>",
00046 "Z position of the ocean surface in world coordinates.");
00047 arguments->getApplicationUsage()->addCommandLineOption(
00048 "--disableShaders",
00049 "Disable use of shaders for the whole application. Also disables most visual effects as they depend on shaders.");
00050 arguments->getApplicationUsage()->addCommandLineOption(
00051 "--disableTextures", "Disable use of textures by default. Can be toggled with the 't' key.");
00052 arguments->getApplicationUsage()->addCommandLineOption("--resw <width>", "Set the viewer width resolution");
00053 arguments->getApplicationUsage()->addCommandLineOption("--resh <height>", "Set the viewer height resolution");
00054 arguments->getApplicationUsage()->addCommandLineOption("--freeMotion", "Sets the main camera to move freely");
00055 arguments->getApplicationUsage()->addCommandLineOption(
00056 "--configfile",
00057 "Indicate config file location (default: data/scenes/cirs.xml). The rest of the options override the values defined in this file.");
00058 arguments->getApplicationUsage()->addCommandLineOption("--v", "Be verbose. (OSG notify level NOTICE)");
00059 arguments->getApplicationUsage()->addCommandLineOption("--vv", "Be much verbose. (OSG notify level DEBUG)");
00060 arguments->getApplicationUsage()->addCommandLineOption("--dataPath <path>",
00061 "Search for models in this path, besides the default ones");
00062 arguments->getApplicationUsage()->addCommandLineOption(
00063 "--debugPhysics [<flag>]",
00064 "Enable physics visualisation. 1 for wireframe, 2 for physics only. For other flag options refer to btIDebugDraw.h");
00065
00066 unsigned int helpType = 0;
00067 if ((helpType = arguments->readHelpType()))
00068 {
00069 arguments->getApplicationUsage()->write(std::cout, helpType);
00070 return 1;
00071 }
00072
00073
00074 osg::setNotifyLevel(osg::FATAL);
00075 if (arguments->read("--v"))
00076 osg::setNotifyLevel(osg::NOTICE);
00077 if (arguments->read("--vv"))
00078 osg::setNotifyLevel(osg::DEBUG_FP);
00079
00080
00081 if (arguments->errors())
00082 {
00083 arguments->writeErrorMessages(std::cout);
00084
00085 return 1;
00086 }
00087
00088 ;
00089
00090 osgDB::Registry::instance()->getDataFilePathList().push_back(std::string("."));
00091
00092 const std::string SIMULATOR_DATA_PATH = std::string(getenv("HOME")) + "/.uwsim/data";
00093 osgDB::Registry::instance()->getDataFilePathList().push_back(std::string(SIMULATOR_DATA_PATH));
00094
00095 osgDB::Registry::instance()->getDataFilePathList().push_back(std::string(UWSIM_ROOT_PATH));
00096 osgDB::Registry::instance()->getDataFilePathList().push_back(std::string(UWSIM_ROOT_PATH) + "/data");
00097 osgDB::Registry::instance()->getDataFilePathList().push_back(std::string(UWSIM_ROOT_PATH) + "/data/scenes");
00098
00099
00100 std::string dataPath("");
00101 while( arguments->read("--dataPath",dataPath))
00102 {
00103 if (dataPath!=std::string(""))
00104 osgDB::Registry::instance()->getDataFilePathList().push_back(dataPath);
00105 }
00106
00107 string configfile = std::string(UWSIM_ROOT_PATH) + "/scenes/cirs.xml";
00108 while (arguments->read("--configfile", configfile))
00109 ;
00110 ConfigFile config(configfile);
00111
00112 ros::init(argc, argv, "UWSim");
00113 ros::start();
00114
00115 SceneBuilder builder(arguments);
00116 builder.loadScene(config);
00117
00118 PhysicsBuilder physicsBuilder;
00119 if (config.enablePhysics)
00120 physicsBuilder.loadPhysics(&builder, config);
00121
00122 int drawPhysics = 0;
00123 if (!arguments->read("--debugPhysics", osg::ArgumentParser::Parameter(drawPhysics))
00124 && arguments->read("--debugPhysics"))
00125 drawPhysics = 2;
00126 boost::shared_ptr<osgbCollision::GLDebugDrawer> debugDrawer;
00127 if (config.enablePhysics && drawPhysics > 0)
00128 {
00129 debugDrawer.reset(new osgbCollision::GLDebugDrawer());
00130 debugDrawer->setDebugMode(drawPhysics);
00131 physicsBuilder.physics->dynamicsWorld->setDebugDrawer(debugDrawer.get());
00132 builder.getRoot()->addChild(debugDrawer->getSceneGraph());
00133 }
00134
00135 ViewBuilder view(config, &builder, arguments);
00136
00137 view.init();
00138 view.getViewer()->realize();
00139 view.getViewer()->frame();
00140
00141 osgViewer::Viewer::Windows windows;
00142 view.getViewer()->getWindows(windows);
00143 windows[0]->setWindowName("UWSim");
00144
00145 double prevSimTime = 0.;
00146 while (!view.getViewer()->done() && ros::ok())
00147 {
00148 ROSInterface::setROSTime(ros::Time::now());
00149 ros::spinOnce();
00150
00151 if (config.enablePhysics)
00152 {
00153 const double currSimTime = view.getViewer()->getFrameStamp()->getSimulationTime();
00154 double elapsed(currSimTime - prevSimTime);
00155 if (view.getViewer()->getFrameStamp()->getFrameNumber() < 3)
00156 elapsed = 1. / 60.;
00157 int subSteps = fmax(0, config.physicsSubSteps);
00158 if (subSteps == 0)
00159 subSteps = ceil(elapsed * config.physicsFrequency);
00160 physicsBuilder.physics->stepSimulation(elapsed, subSteps, 1 / config.physicsFrequency);
00161 prevSimTime = currSimTime;
00162 if (debugDrawer)
00163 {
00164 debugDrawer->BeginDraw();
00165 physicsBuilder.physics->dynamicsWorld->debugDraw();
00166 debugDrawer->EndDraw();
00167 }
00168 }
00169
00170 view.getViewer()->frame();
00171 }
00172 if (ros::ok())
00173 ros::shutdown();
00174
00175 ROS_INFO("Finished");
00176
00177 return 0;
00178 }