image_view.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 
00031 #include <QtGlobal>
00032 #include <QTimer>
00033 
00034 #include "ogre_tools/qt_ogre_render_window.h"
00035 #include "ogre_tools/render_system.h"
00036 #include "ogre_tools/initialization.h"
00037 #include "rviz/image/ros_image_texture.h"
00038 
00039 #include "ros/ros.h"
00040 #include <ros/package.h>
00041 
00042 #include <OGRE/OgreRoot.h>
00043 #include <OGRE/OgreRenderWindow.h>
00044 #include <OGRE/OgreSceneManager.h>
00045 #include <OGRE/OgreViewport.h>
00046 #include <OGRE/OgreRectangle2D.h>
00047 #include <OGRE/OgreMaterial.h>
00048 #include <OGRE/OgreMaterialManager.h>
00049 #include <OGRE/OgreTextureUnitState.h>
00050 
00051 #include "image_view.h"
00052 
00053 using namespace ogre_tools;
00054 using namespace rviz;
00055 
00056 ImageView::ImageView( QWidget* parent )
00057   : QtOgreRenderWindow( RenderSystem::get(), parent )
00058 {
00059   setAutoRender(false);
00060   scene_manager_ = ogre_root_->createSceneManager( Ogre::ST_GENERIC, "TestSceneManager" );
00061 }
00062 
00063 ImageView::~ImageView()
00064 {
00065   delete texture_;
00066 }
00067 
00068 void ImageView::showEvent( QShowEvent* event )
00069 {
00070   QtOgreRenderWindow::showEvent( event );
00071 
00072   ogre_tools::V_string paths;
00073   paths.push_back(ros::package::getPath(ROS_PACKAGE_NAME) + "/ogre_media/textures");
00074   ogre_tools::initializeResources(paths);
00075 
00076   setCamera( scene_manager_->createCamera( "Camera" ));
00077 
00078   std::string resolved_image = nh_.resolveName("image");
00079   if( resolved_image == "/image" )
00080   {
00081     ROS_WARN("image topic has not been remapped");
00082   }
00083 
00084   std::stringstream title;
00085   title << "rviz Image Viewer [" << resolved_image << "]";
00086   setWindowTitle( QString::fromStdString( title.str() ));
00087 
00088   texture_ = new ROSImageTexture(nh_);
00089   texture_->setTopic("image");
00090 
00091   Ogre::MaterialPtr material =
00092     Ogre::MaterialManager::getSingleton().create( "Material",
00093                                                   Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00094   material->setCullingMode(Ogre::CULL_NONE);
00095   material->getTechnique(0)->getPass(0)->setDepthWriteEnabled(true);
00096   material->getTechnique(0)->setLightingEnabled(false);
00097   Ogre::TextureUnitState* tu = material->getTechnique(0)->getPass(0)->createTextureUnitState();
00098   tu->setTextureName(texture_->getTexture()->getName());
00099   tu->setTextureFiltering( Ogre::TFO_NONE );
00100 
00101   Ogre::Rectangle2D* rect = new Ogre::Rectangle2D(true);
00102   rect->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00103   rect->setMaterial(material->getName());
00104   rect->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00105   Ogre::AxisAlignedBox aabb;
00106   aabb.setInfinite();
00107   rect->setBoundingBox(aabb);
00108 
00109   Ogre::SceneNode* node = scene_manager_->getRootSceneNode()->createChildSceneNode();
00110   node->attachObject(rect);
00111   node->setVisible(true);
00112 
00113   QTimer* timer = new QTimer( this );
00114   connect( timer, SIGNAL( timeout() ), this, SLOT( onTimer() ));
00115   timer->start( 33 );
00116 }
00117 
00118 void ImageView::onTimer()
00119 {
00120   ros::spinOnce();
00121 
00122   static bool first = true;
00123   try
00124   {
00125     if( texture_->update() )
00126     {
00127       if( first )
00128       {
00129         first = false;
00130 
00131         resize( texture_->getWidth(), texture_->getHeight() );
00132       }
00133     }
00134 
00135     ogre_root_->renderOneFrame();
00136   }
00137   catch( UnsupportedImageEncoding& e )
00138   {
00139     ROS_ERROR("%s", e.what());
00140   }
00141 
00142   if( !nh_.ok() )
00143   {
00144     close();
00145   }
00146 }


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52