VirtualCamera.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 VIRTUALCAMERA_H_
00014 #define VIRTUALCAMERA_H_
00015 
00016 #include "SimulatorConfig.h"
00017 #include "CustomWidget.h"
00018 #include "ConfigXMLParser.h"
00019 #include "UWSimUtils.h"
00020 
00021 #include <osgViewer/Viewer>
00022 #include <osgGA/NodeTrackerManipulator>
00023 #include <osg/Camera>
00024 #include <osg/Texture2D>
00025 #include <osgGA/GUIEventHandler>
00026 #include <osg/Geometry>
00027 #include <osg/NodeTrackerCallback>
00028 #include <osg/Switch>
00029 #include <osg/Geode>
00030 #include <osg/Geometry>
00031 #include <osg/Vec3>
00032 #include <osg/Drawable>
00033 #include <osg/LineWidth>
00034 #include <osg/io_utils>
00035 
00036 #include <GL/glu.h>
00037 
00038 #include <ros/ros.h>
00039 
00041 class VirtualCamera : public CustomWidget, public osg::Referenced
00042 {
00043 
00044   //Custom node tracking
00045   class MyNodeTrackerCallback : public osg::NodeTrackerCallback
00046   {
00047     osg::ref_ptr<osg::Camera> osgcamera;
00048     osg::ref_ptr<osg::Image> zbuffer;
00049     osg::Matrixd previous_wMc;
00050 
00051     double show_path_;
00052 
00053     ros::Time previous, current;
00054 
00055     void operator()(osg::Node *node, osg::NodeVisitor *nv)
00056     {
00057       //std::cerr << "Node Tracker callback" << std::endl;
00058       osg::Matrixd m;
00059       //((osg::Transform*)node)->computeWorldToLocalMatrix(m,nv);
00060       m = osg::computeWorldToLocal(nv->getNodePath());
00061       traverse(node, nv);
00062       osgcamera->setViewMatrix(m);
00063 
00064       //Check for the time ellapsed since the last time. If greater than showfov rate (if defined),
00065       //and displacement greater than min_displacement, attach the current FOV to the root
00066       current = ros::Time::now();
00067       if (show_path_ > 0 && (current - previous).toSec() > show_path_)
00068       {
00069         previous = current;
00070 
00071         osg::Matrixd wMc = osgcamera->getViewMatrix();
00072         if ((wMc.getTrans() - previous_wMc.getTrans()).length() > 0.15)
00073         {
00074           previous_wMc = wMc;
00075 
00076           osg::Matrixd projm = osgcamera->getProjectionMatrix();
00077 
00078           GLint viewport[4];
00079           viewport[0] = osgcamera->getViewport()->x();
00080           viewport[1] = osgcamera->getViewport()->y();
00081           viewport[2] = osgcamera->getViewport()->width();
00082           viewport[3] = osgcamera->getViewport()->height();
00083 
00084           double z_b[4];
00085           z_b[0] = ((float*)zbuffer->data())[0];
00086           z_b[1] = ((float*)zbuffer->data())[viewport[2] - 1];
00087           z_b[2] = ((float*)zbuffer->data())[viewport[2] * viewport[3] - 1];
00088           z_b[3] = ((float*)zbuffer->data())[viewport[2] * viewport[3] - viewport[2]];
00089 
00090           if (z_b[0] > 0 || z_b[1] > 0 || z_b[2] > 0 || z_b[3] > 0)
00091           {
00092             double X[4], Y[4], Z[4];
00093             gluUnProject(0, 0, z_b[0] * 0.9999, wMc.ptr(), projm.ptr(), viewport, &X[0], &Y[0], &Z[0]);
00094             gluUnProject(viewport[2], 0, z_b[1] * 0.9999, wMc.ptr(), projm.ptr(), viewport, &X[1], &Y[1], &Z[1]);
00095             gluUnProject(viewport[2], viewport[3], z_b[2] * 0.9999, wMc.ptr(), projm.ptr(), viewport, &X[2], &Y[2],
00096                          &Z[2]);
00097             gluUnProject(0, viewport[3], z_b[3] * 0.9999, wMc.ptr(), projm.ptr(), viewport, &X[3], &Y[3], &Z[3]);
00098 
00099             cameraPathVertices->push_back(osg::Vec3d(X[0], Y[0], Z[0]));
00100             cameraPathVertices->push_back(osg::Vec3d(X[1], Y[1], Z[1]));
00101             cameraPathVertices->push_back(osg::Vec3d(X[2], Y[2], Z[2]));
00102             cameraPathVertices->push_back(osg::Vec3d(X[3], Y[3], Z[3]));
00103 
00104             cameraPathVertices->push_back(osg::Vec3d(X[0], Y[0], Z[0]));
00105             cameraPathGeometry->setVertexArray(cameraPathVertices);
00106             ((osg::DrawArrays*)cameraPathPrset.get())->setFirst(0);
00107             ((osg::DrawArrays*)cameraPathPrset.get())->setCount(cameraPathVertices->size());
00108           }
00109         }
00110       }
00111     }
00112   public:
00113     //Attributes that store the camera path projected on the terrain
00114     osg::ref_ptr<osg::Switch> cameraPathSwitch;
00115     osg::ref_ptr<osg::Geode> cameraPathGeode;
00116     osg::ref_ptr<osg::Geometry> cameraPathGeometry;
00117     osg::ref_ptr<osg::Vec3Array> cameraPathVertices;
00118     osg::ref_ptr<osg::Vec4Array> cameraPathColors;
00119     osg::ref_ptr<osg::PrimitiveSet> cameraPathPrset;
00120 
00121     MyNodeTrackerCallback(osg::Group *uwsim_root, osg::Image *zbuffer, osg::Camera *cam)
00122     {
00123       this->zbuffer = zbuffer;
00124       this->osgcamera = cam;
00125       show_path_ = 0;
00126 
00127       previous = ros::Time::now();
00128 
00129       cameraPathSwitch = new osg::Switch();
00130       uwsim_root->addChild(cameraPathSwitch);
00131       cameraPathSwitch->setAllChildrenOn();
00132 
00133       cameraPathGeode = new osg::Geode();
00134       cameraPathGeometry = new osg::Geometry();
00135       cameraPathVertices = new osg::Vec3Array;
00136       cameraPathGeometry->setVertexArray(cameraPathVertices);
00137       cameraPathColors = new osg::Vec4Array;
00138       cameraPathColors->push_back(osg::Vec4(1.0f, 1.0f, 0.0f, 1.0f)); //TODO: Allow user set color
00139       cameraPathGeometry->setColorArray(cameraPathColors);
00140       cameraPathGeometry->setColorBinding(osg::Geometry::BIND_OVERALL);
00141       cameraPathPrset = new osg::DrawArrays(osg::PrimitiveSet::LINE_STRIP, 0, 0);
00142       cameraPathGeometry->addPrimitiveSet(cameraPathPrset);
00143       cameraPathGeode->addDrawable(cameraPathGeometry);
00144 
00145       osg::LineWidth* linewidth = new osg::LineWidth();
00146       linewidth->setWidth(3.0f);
00147       cameraPathGeode->getOrCreateStateSet()->setAttributeAndModes(linewidth, osg::StateAttribute::ON);
00148 
00149       UWSimGeometry::applyStateSets(cameraPathGeode);
00150       cameraPathSwitch->addChild(cameraPathGeode);
00151 
00152     }
00153 
00154     void showPath(double rate)
00155     {
00156       show_path_ = rate;
00157     }
00158   };
00159 
00160 public:
00161   std::string name;
00162   osg::ref_ptr<osg::Group> uwsim_root;
00163   osg::ref_ptr<osg::Camera> textureCamera;
00164   osg::Node *trackNode;
00165   osg::ref_ptr<MyNodeTrackerCallback> node_tracker;
00166 
00167   int width, height, range;
00168   double fx, fy, cx, cy; 
00169   double aspectRatio, fov, far, near, k;
00170   double baseline; //Only for stereo. Default=0
00171   double Tx, Ty; //Only for stereo.
00172   std::string frameId; //Default=""
00173   int paramsOn;
00174   int bw; //BlackWhite camera
00175   int widget; //Widget available or not
00176 
00177   osg::ref_ptr<osg::Image> renderTexture; //RGB image
00178   osg::ref_ptr<osg::Image> depthTexture; //Range image
00179 
00180   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, double fov, double range);
00181   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height, double fov,
00182                 double aspectRatio);
00183   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height);
00184   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00185                 Parameters *params);
00186   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height, double baseline,
00187                 std::string frameId);
00188   VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height, double baseline,
00189                 std::string frameId, Parameters *params, int range, int bw);
00190   VirtualCamera();
00191 
00192   void init(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height, double baseline,
00193             std::string frameId, Parameters *params, int range, double fov, double aspectRatio, double near, double far,
00194             int bw, int widget);
00195 
00196   void createCamera();
00197 
00198   void showPath(double rate)
00199   {
00200     node_tracker->showPath(rate);
00201   }
00202 
00203   //Interface to be implemented by widgets. Build a widget window with the data to be displayed
00204   osg::ref_ptr<osgWidget::Window> getWidgetWindow();
00205 };
00206 
00207 #endif /* VIRTUALCAMERA_H_ */


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