VirtualCamera.cpp
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 #include <uwsim/VirtualCamera.h>
00014 #include <uwsim/UWSimUtils.h>
00015 #include <uwsim/SceneBuilder.h>
00016 #include <iostream>
00017 
00018 class UpdateUnderWater : public osg::Uniform::Callback
00019 {
00020 public:
00021   UpdateUnderWater(osg::Camera* camera) :
00022       mCamera(camera)
00023   {
00024   }
00025   virtual void operator ()(osg::Uniform* u, osg::NodeVisitor*)
00026   {
00027     u->set(true); //TODO: Should check waterheight!!
00028   }
00029 
00030 protected:
00031   osg::Camera* mCamera;
00032 };
00033 
00034 class UpdateEye : public osg::Uniform::Callback
00035 {
00036 public:
00037   UpdateEye(osg::Camera* camera) :
00038       mCamera(camera)
00039   {
00040   }
00041   virtual void operator ()(osg::Uniform* u, osg::NodeVisitor*)
00042   {
00043     osg::Vec3d eye, center, up;
00044     mCamera->getViewMatrixAsLookAt(eye, center, up);
00045     u->set(eye);
00046   }
00047 
00048 protected:
00049   osg::Camera* mCamera;
00050 };
00051 
00052 class UpdateVMI : public osg::Uniform::Callback
00053 {
00054 public:
00055   UpdateVMI(osg::Camera* camera) :
00056       mCamera(camera)
00057   {
00058   }
00059   virtual void operator ()(osg::Uniform* u, osg::NodeVisitor*)
00060   {
00061     u->set(mCamera->getInverseViewMatrix());
00062   }
00063 
00064 protected:
00065   osg::Camera* mCamera;
00066 };
00067 
00068 VirtualCamera::VirtualCamera()
00069 {
00070 }
00071 
00072 void VirtualCamera::init(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00073                          double baseline, std::string frameId, Parameters *params, int range, double fov,
00074                          double aspectRatio, double near, double far, int bw, int widget)
00075 {
00076   this->uwsim_root = uwsim_root;
00077   this->name = name;
00078 
00079   this->trackNode = trackNode;
00080   //Add a switchable frame geometry on the camera frame
00081   osg::ref_ptr < osg::Node > axis = UWSimGeometry::createSwitchableFrame();
00082   this->trackNode->asGroup()->addChild(axis);
00083 
00084   this->width = width;
00085   this->height = height;
00086   this->baseline = baseline;
00087   this->frameId = frameId;
00088   this->fov = fov;
00089   this->aspectRatio = aspectRatio;
00090   this->near = near;
00091   this->far = far;
00092   if (params != NULL)
00093   {
00094     this->fx = params->fx;
00095     this->fy = params->fy;
00096     this->far = params->f;
00097     this->near = params->n;
00098     this->cx = params->x0;
00099     this->cy = params->y0;
00100     this->k = params->k;
00101     this->paramsOn = 1;
00102   }
00103   else
00104     this->paramsOn = 0;
00105   this->range = range;
00106   this->bw = bw;
00107   this->widget = widget;
00108 
00109   if (!range)
00110   {
00111     renderTexture = new osg::Image();
00112     renderTexture->allocateImage(width, height, 1, GL_RGB, GL_UNSIGNED_BYTE);
00113   }
00114   else
00115   {
00116     depthTexture = new osg::Image();
00117     depthTexture->allocateImage(width, height, 1, GL_DEPTH_COMPONENT, GL_FLOAT);
00118   }
00119 
00120   createCamera();
00121 }
00122 
00123 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, double fov,
00124                              double range)
00125 { //Used in multibeam
00126   //Z-buffer has very low resolution near far plane so we extend it and cut far plane later.
00127   init(uwsim_root, name, trackNode, 1, width, 0.0, "", NULL, 1, fov, 1.0 / width, 0.8, range * 1.2, 0, 0);
00128 
00129 }
00130 
00131 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00132                              double fov, double aspectRatio)
00133 { //Used in structured light projector as shadow camera
00134   init(uwsim_root, name, trackNode, width, height, 0.0, "", NULL, 1, fov, aspectRatio, 0.1, 20, 0, 0);
00135 }
00136 
00137 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00138                              double baseline, std::string frameId)
00139 {
00140   init(uwsim_root, name, trackNode, width, height, baseline, frameId, NULL, 0, 50, 1.33, 0.18, 20, 0, 1);
00141 }
00142 
00143 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00144                              double baseline, std::string frameId, Parameters *params, int range, int bw)
00145 {
00146   init(uwsim_root, name, trackNode, width, height, baseline, frameId, params, range, 50, 1.33, 0.18, 20, bw, 1);
00147 }
00148 
00149 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height,
00150                              Parameters *params)
00151 {
00152   init(uwsim_root, name, trackNode, width, height, 0.0, "", params, 0, 50, 1.33, 0.18, 20, 0, 1);
00153 }
00154 
00155 VirtualCamera::VirtualCamera(osg::Group *uwsim_root, std::string name, osg::Node *trackNode, int width, int height)
00156 {
00157   init(uwsim_root, name, trackNode, width, height, 0.0, "", NULL, 0, 50, 1.33, 0.18, 20, 0, 1);
00158 }
00159 
00160 void VirtualCamera::createCamera()
00161 {
00162   textureCamera = new osg::Camera;
00163   textureCamera->setReferenceFrame(osg::Transform::ABSOLUTE_RF);
00164   textureCamera->setClearMask(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
00165   textureCamera->setViewport(0, 0, width, height);
00166 
00167   // Frame buffer objects are the best option
00168   textureCamera->setRenderTargetImplementation(osg::Camera::FRAME_BUFFER_OBJECT);
00169 
00170   // We need to render to the texture BEFORE we render to the screen
00171   textureCamera->setRenderOrder(osg::Camera::PRE_RENDER);
00172 
00173   // The camera will render into the texture that we created earlier
00174   if (!range)
00175     textureCamera->attach(osg::Camera::COLOR_BUFFER, renderTexture.get());
00176   else
00177     textureCamera->attach(osg::Camera::DEPTH_BUFFER, depthTexture.get());
00178 
00179   textureCamera->setName("CamViewCamera");
00180   textureCamera->setComputeNearFarMode(osg::CullSettings::DO_NOT_COMPUTE_NEAR_FAR);
00181 
00182   if (!paramsOn)
00183   {
00184     //set default fov, near and far parameters (default parameters on init function as some of them change depending on camera type (shadow,depth,texture))
00185     textureCamera->setProjectionMatrixAsPerspective(fov, aspectRatio, near, far);
00186     osg::Matrixd m;
00187     m = textureCamera->getProjectionMatrix();
00188     fx = m(0, 0) * width / 2.0;
00189     fy = m(1, 1) * height / 2.0;
00190     cx = -(m(0, 2) - 1) * width / 2.0;
00191     cy = -(m(1, 2) - 1) * height / 2.0;
00192   }
00193   else
00194   {
00195     //set opengl projection matrix from calibration parameters fx, fy, w, h, x0, y0, n
00196     // How to obtain opengl projection matrix from camera calibration parameters:
00197     // 2.0*fx/w    2.0*k/w    1-2*x0/w       0
00198     // 0          2.0*fy/h   1-2*y0/h       0
00199     // 0           0          (f+n)/(n-f)    2*fn/(n-f)
00200     // 0           0         -1              0
00201     //osg::Matrixd m(2.0*fx/width,2.0*k/width,1-(2*cx/width),0,0,2.0*fy/height,1-(2.0*cy/height),0,0,0,(far+near)/(near-far),2*far*near/(near-far),0,0,-1,0); //osg Uses trasposed matrix
00202     osg::Matrixd m(2.0 * fx / width, 0, 0, 0, 2.0 * k / width, 2.0 * fy / height, 0, 0, 1 - (2 * cx / width),
00203                    1 - (2.0 * cy / height), (far + near) / (near - far), -1, 0, 0, 2 * far * near / (near - far), 0);
00204     textureCamera->setProjectionMatrix(m);
00205 
00206   }
00207 
00208   Tx = (-fx * baseline);
00209   Ty = 0.0;
00210 
00211   node_tracker = new MyNodeTrackerCallback(uwsim_root, depthTexture, textureCamera);
00212   trackNode->setEventCallback(node_tracker);
00213 
00214   //Uniforms for independence from main camera (underwater effects on shaders)
00215   osg::Uniform* u = new osg::Uniform("osgOcean_EyeUnderwater", true);
00216   u->setUpdateCallback(new UpdateUnderWater(textureCamera));
00217 
00218   textureCamera->getOrCreateStateSet()->addUniform(u);
00219   osg::Vec3d eye, center, up;
00220   textureCamera->getViewMatrixAsLookAt(eye, center, up);
00221   osg::Uniform* u2 = new osg::Uniform("osgOcean_Eye", eye);
00222   u2->setUpdateCallback(new UpdateEye(textureCamera));
00223   textureCamera->getOrCreateStateSet()->addUniform(u2);
00224 
00225   osg::Uniform* u3 = new osg::Uniform("osg_ViewMatrixInverse", textureCamera->getInverseViewMatrix());
00226   u3->setUpdateCallback(new UpdateVMI(textureCamera));
00227   textureCamera->getOrCreateStateSet()->addUniform(u3);
00228 
00229 }
00230 
00231 osg::ref_ptr<osgWidget::Window> VirtualCamera::getWidgetWindow()
00232 {
00233   osg::ref_ptr < osgWidget::Box > box = new osgWidget::Box("VirtualCameraBox", osgWidget::Box::HORIZONTAL, true);
00234   osg::ref_ptr < osgWidget::Widget > widget = new osgWidget::Widget("VirtualCameraWidget", width, height);
00235   if (!range)
00236     widget->setImage(renderTexture.get(), true, false);
00237   else
00238     widget->setImage(depthTexture.get(), true, false);
00239   box->addWidget(widget.get());
00240   box->getBackground()->setColor(1.0f, 0.0f, 0.0f, 0.8f);
00241   box->attachMoveCallback();
00242   box->attachScaleCallback();
00243   return box;
00244 }


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