UWSimUtils.h
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 #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 
00029 #include <btBulletDynamicsCommon.h>
00030 
00031 //Node data used to check if an object is catchable or not.
00032 class NodeDataType : public osg::Referenced
00033 {
00034 public:
00035   NodeDataType(int catcha, double origP[3] = NULL, double origR[3] = NULL)
00036   {
00037     catchable = catcha;
00038     if (origP != NULL)
00039     {
00040       originalPosition[0] = origP[0];
00041       originalPosition[1] = origP[1];
00042       originalPosition[2] = origP[2];
00043     }
00044     if (origR != NULL)
00045     {
00046       originalRotation[0] = origR[0];
00047       originalRotation[1] = origR[1];
00048       originalRotation[2] = origR[2];
00049     }
00050     rigidBody = NULL; //initiated if physics is ON
00051   }
00052   ;
00053   int catchable;
00054   double originalPosition[3], originalRotation[3];
00055   btRigidBody * rigidBody;
00056 
00057 };
00058 
00059 typedef std::vector<osg::Node*> nodeListType;
00060 
00061 class findNodeVisitor : public osg::NodeVisitor
00062 {
00063 public:
00064 
00065   findNodeVisitor();
00066 
00067   findNodeVisitor(const std::string &searchName);
00068 
00069   virtual void apply(osg::Node &searchNode);
00070 
00071   void setNameToFind(const std::string &searchName);
00072 
00073   osg::Node* getFirst();
00074 
00075   nodeListType& getNodeList()
00076   {
00077     return foundNodeList;
00078   }
00079 
00080 private:
00081 
00082   std::string searchForName;
00083   nodeListType foundNodeList;
00084 
00085 };
00086 
00087 class findRoutedNode
00088 {
00089 public:
00090 
00091   findRoutedNode();
00092 
00093   findRoutedNode(const std::string &searchName);
00094   void setNameToFind(const std::string &searchName);
00095   void find(osg::ref_ptr<osg::Node> searchNode);
00096   osg::Node* getFirst();
00097 
00098 private:
00099 
00100   findNodeVisitor nodeVisitor;
00101   std::string searchRoute;
00102   nodeListType rootList;
00103 
00104 };
00105 
00106 osg::Node * findRN(std::string target, osg::Group * root);
00107 
00108 class ScopedTimer
00109 {
00110 public:
00111   ScopedTimer(const std::string& description, std::ostream& output_stream = std::cout, bool endline_after_time = true) :
00112       _output_stream(output_stream), _start(), _endline_after_time(endline_after_time)
00113   {
00114     _output_stream << description << std::flush;
00115     _start = osg::Timer::instance()->tick();
00116   }
00117 
00118   ~ScopedTimer()
00119   {
00120     osg::Timer_t end = osg::Timer::instance()->tick();
00121     _output_stream << osg::Timer::instance()->delta_s(_start, end) << "s";
00122     if (_endline_after_time)
00123       _output_stream << std::endl;
00124     else
00125       _output_stream << std::flush;
00126   }
00127 
00128 private:
00129   std::ostream& _output_stream;
00130   osg::Timer_t _start;
00131   bool _endline_after_time;
00132 };
00133 
00134 class UWSimGeometry
00135 {
00136 public:
00137   static osg::Node* createFrame(double radius = 0.015, double length = 0.2);
00138   static osg::Node* createSwitchableFrame(double radius = 0.015, double length = 0.2);
00139   static osg::Node* createOSGBox(osg::Vec3 size);
00140   static osg::Node* createOSGCylinder(double radius, double height);
00141   static osg::Node* createOSGSphere(double radius);
00142 
00143   static osg::Node * retrieveResource(std::string name);
00144   static osg::Node * loadGeometry(boost::shared_ptr<Geometry> geom);
00145 
00147   static void applyStateSets(osg::Node*);
00148 
00149 private:
00150 
00151 };
00152 
00153 /***********/
00154 
00155 // Visitor to return the world coordinates of a node.
00156 // It traverses from the starting node to the parent.
00157 // The first time it reaches a root node, it stores the world coordinates of 
00158 // the node it started from.  The world coordinates are found by concatenating all 
00159 // the matrix transforms found on the path from the start node to the root node.
00160 class getWorldCoordOfNodeVisitor : public osg::NodeVisitor
00161 {
00162 public:
00163   getWorldCoordOfNodeVisitor();
00164   virtual void apply(osg::Node &node);
00165   boost::shared_ptr<osg::Matrix> giveUpDaMat();
00166 private:
00167   bool done;
00168   boost::shared_ptr<osg::Matrix> wcMatrix;
00169 };
00170 
00171 // Given a valid node placed in a scene under a transform, return the
00172 // world coordinates in an osg::Matrix.
00173 // Creates a visitor that will update a matrix representing world coordinates
00174 // of the node, return this matrix.
00175 // (This could be a class member for something derived from node also.
00176 boost::shared_ptr<osg::Matrix> getWorldCoords(osg::Node* node);
00177 
00178 //Class to get all the catchable objects
00179 
00180 class GetCatchableObjects : public osg::NodeVisitor
00181 {
00182 public:
00183   GetCatchableObjects();
00184   virtual void apply(osg::Node &node);
00185   nodeListType& getNodeList()
00186   {
00187     return foundNodeList;
00188   }
00189 private:
00190   nodeListType foundNodeList;
00191 };
00192 
00193 #endif
00194 


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