Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013 #ifndef UWSIMUTILS_H
00014 #define UWSIMUTILS_H
00015
00016 #include <osg/NodeVisitor>
00017 #include <osg/Node>
00018 #include <osg/Timer>
00019
00020 #include <iostream>
00021 #include <vector>
00022
00023 #include "ConfigXMLParser.h"
00024 #include <resource_retriever/retriever.h>
00025 #include <osgDB/Registry>
00026 #include <osgDB/FileNameUtils>
00027 #include <osg/Version>
00028 #include <osgText/Text>
00029
00030 #include <btBulletDynamicsCommon.h>
00031
00032
00033 class NodeDataType : public osg::Referenced
00034 {
00035 public:
00036 NodeDataType(int catcha, double origP[3] = NULL, double origR[3] = NULL)
00037 {
00038 catchable = catcha;
00039 if (origP != NULL)
00040 {
00041 originalPosition[0] = origP[0];
00042 originalPosition[1] = origP[1];
00043 originalPosition[2] = origP[2];
00044 }
00045 if (origR != NULL)
00046 {
00047 originalRotation[0] = origR[0];
00048 originalRotation[1] = origR[1];
00049 originalRotation[2] = origR[2];
00050 }
00051 rigidBody = NULL;
00052 }
00053 ;
00054 int catchable;
00055 double originalPosition[3], originalRotation[3];
00056 btRigidBody * rigidBody;
00057
00058 };
00059
00060 typedef std::vector<osg::Node*> nodeListType;
00061
00062 class findNodeVisitor : public osg::NodeVisitor
00063 {
00064 public:
00065
00066 findNodeVisitor();
00067
00068 findNodeVisitor(const std::string &searchName);
00069
00070 virtual void apply(osg::Node &searchNode);
00071
00072 void setNameToFind(const std::string &searchName);
00073
00074 osg::Node* getFirst();
00075
00076 nodeListType& getNodeList()
00077 {
00078 return foundNodeList;
00079 }
00080
00081 private:
00082
00083 std::string searchForName;
00084 nodeListType foundNodeList;
00085
00086 };
00087
00088 class findRoutedNode
00089 {
00090 public:
00091
00092 findRoutedNode();
00093
00094 findRoutedNode(const std::string &searchName);
00095 void setNameToFind(const std::string &searchName);
00096 void find(osg::ref_ptr<osg::Node> searchNode);
00097 osg::Node* getFirst();
00098
00099 private:
00100
00101 findNodeVisitor nodeVisitor;
00102 std::string searchRoute;
00103 nodeListType rootList;
00104
00105 };
00106
00107 osg::Node * findRN(std::string target, osg::Group * root);
00108
00109 class ScopedTimer
00110 {
00111 public:
00112 ScopedTimer(const std::string& description, std::ostream& output_stream = std::cout, bool endline_after_time = true) :
00113 _output_stream(output_stream), _start(), _endline_after_time(endline_after_time)
00114 {
00115 _output_stream << description << std::flush;
00116 _start = osg::Timer::instance()->tick();
00117 }
00118
00119 ~ScopedTimer()
00120 {
00121 osg::Timer_t end = osg::Timer::instance()->tick();
00122 _output_stream << osg::Timer::instance()->delta_s(_start, end) << "s";
00123 if (_endline_after_time)
00124 _output_stream << std::endl;
00125 else
00126 _output_stream << std::flush;
00127 }
00128
00129 private:
00130 std::ostream& _output_stream;
00131 osg::Timer_t _start;
00132 bool _endline_after_time;
00133 };
00134
00135 class UWSimGeometry
00136 {
00137 public:
00138 static osg::Node* createFrame(double radius = 0.015, double length = 0.2);
00139 static osg::Node* createSwitchableFrame(double radius = 0.015, double length = 0.2, unsigned int mask=0x40);
00140 static osg::Node* createOSGBox(osg::Vec3 size);
00141 static osg::Node* createOSGCylinder(double radius, double height);
00142 static osg::Node* createOSGSphere(double radius);
00143 static osg::Node* createLabel(std::string text,double charSize=0.02, int bb=1, osg::Vec4 color=osg::Vec4(1,1,1,1) );
00144
00145 static osg::Node * retrieveResource(std::string name);
00146 static osg::Node * loadGeometry(boost::shared_ptr<Geometry> geom);
00147 private:
00148
00149 };
00150
00151
00152
00153
00154
00155
00156
00157
00158 class getWorldCoordOfNodeVisitor : public osg::NodeVisitor
00159 {
00160 public:
00161 getWorldCoordOfNodeVisitor();
00162 virtual void apply(osg::Node &node);
00163 boost::shared_ptr<osg::Matrix> giveUpDaMat();
00164 private:
00165 bool done;
00166 boost::shared_ptr<osg::Matrix> wcMatrix;
00167 };
00168
00169
00170
00171
00172
00173
00174 boost::shared_ptr<osg::Matrix> getWorldCoords(osg::Node* node);
00175
00176
00177
00178 class GetCatchableObjects : public osg::NodeVisitor
00179 {
00180 public:
00181 GetCatchableObjects();
00182 virtual void apply(osg::Node &node);
00183 nodeListType& getNodeList()
00184 {
00185 return foundNodeList;
00186 }
00187 private:
00188 nodeListType foundNodeList;
00189 };
00190
00191
00192
00193
00194
00195
00196 class AbstractDredgeTool
00197 {
00198 public:
00199
00200 virtual boost::shared_ptr<osg::Matrix> getDredgePosition() =0;
00201
00202 virtual void dredgedParticles(int nparticles) =0;
00203 };
00204
00205 class DynamicHF : public osg::Drawable::UpdateCallback
00206 {
00207 public:
00208 DynamicHF(osg::HeightField* heightField, boost::shared_ptr<osg::Matrix> mat, std::vector<boost::shared_ptr<AbstractDredgeTool> > tools);
00209 virtual void update( osg::NodeVisitor*, osg::Drawable*drawable );
00210 private:
00211 osg::HeightField* heightField;
00212 boost::shared_ptr<osg::Matrix> objectMat;
00213 std::vector<boost::shared_ptr<AbstractDredgeTool> > dredgeTools;
00214 };
00215
00216 osg::Node* createHeightField(osg::ref_ptr<osg::Node> object, std::string texFile, double percent, const std::vector<boost::shared_ptr<SimulatedIAUV> > vehicles);
00217 #endif
00218