overlay_utils.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "overlay_utils.h"
00037 
00038 namespace jsk_rviz_plugin
00039 {
00040   ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer):
00041     pixel_buffer_(pixel_buffer)
00042   {
00043     pixel_buffer_->lock( Ogre::HardwareBuffer::HBL_NORMAL );
00044   }
00045 
00046   ScopedPixelBuffer::~ScopedPixelBuffer()
00047   {
00048     pixel_buffer_->unlock();
00049   }
00050 
00051   Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer()
00052   {
00053     return pixel_buffer_;
00054   }
00055 
00056   QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height)
00057   {
00058     const Ogre::PixelBox& pixelBox = pixel_buffer_->getCurrentLock();
00059     Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
00060     memset(pDest, 0, width * height);
00061     return QImage(pDest, width, height, QImage::Format_ARGB32 );
00062   }
00063 
00064   QImage ScopedPixelBuffer::getQImage(
00065     unsigned int width, unsigned int height, QColor& bg_color)
00066   {
00067     QImage Hud = getQImage(width, height);
00068     for (unsigned int i = 0; i < width; i++) {
00069       for (unsigned int j = 0; j < height; j++) {
00070         Hud.setPixel(i, j, bg_color.rgba());
00071       }
00072     }
00073     return Hud;
00074   }
00075 
00076   QImage ScopedPixelBuffer::getQImage(OverlayObject& overlay)
00077   {
00078     return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight());
00079   }
00080   
00081   QImage ScopedPixelBuffer::getQImage(OverlayObject& overlay,
00082                                       QColor& bg_color)
00083   {
00084     return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(),
00085                      bg_color);
00086   }
00087   
00088   OverlayObject::OverlayObject(const std::string& name)
00089     : name_(name)
00090   {
00091     std::string material_name = name_ + "Material";
00092     Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr();
00093     overlay_ = mOverlayMgr->create(name_);
00094     panel_ = static_cast<Ogre::PanelOverlayElement*> (
00095       mOverlayMgr->createOverlayElement("Panel", name_ + "Panel"));
00096     panel_->setMetricsMode(Ogre::GMM_PIXELS);
00097     
00098     panel_material_
00099       = Ogre::MaterialManager::getSingleton().create(
00100         material_name,
00101         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00102     panel_->setMaterialName(panel_material_->getName());
00103     overlay_->add2D(panel_);
00104   }
00105 
00106   OverlayObject::~OverlayObject()
00107   {
00108     hide();
00109     panel_material_->unload();
00110     Ogre::MaterialManager::getSingleton().remove(panel_material_->getName());
00111     // Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr();
00112     // mOverlayMgr->destroyOverlayElement(panel_);
00113     //delete panel_;
00114     //delete overlay_;
00115   }
00116 
00117   std::string OverlayObject::getName()
00118   {
00119     return name_;
00120   }
00121 
00122   void OverlayObject::hide()
00123   {
00124     if (overlay_->isVisible()) {
00125       overlay_->hide();
00126     }
00127   }
00128 
00129   void OverlayObject::show()
00130   {
00131     if (!overlay_->isVisible()) {
00132       overlay_->show();
00133     }
00134   }
00135 
00136   bool OverlayObject::isTextureReady()
00137   {
00138     return !texture_.isNull();
00139   }
00140 
00141   bool OverlayObject::updateTextureSize(unsigned int width, unsigned int height)
00142   {
00143     const std::string texture_name = name_ + "Texture";
00144     if (!isTextureReady() ||
00145         ((width != texture_->getWidth()) ||
00146          (height != texture_->getHeight()))) {
00147       if (isTextureReady()) {
00148         Ogre::TextureManager::getSingleton().remove(texture_name);
00149         panel_material_->getTechnique(0)->getPass(0)
00150           ->removeAllTextureUnitStates();
00151       }
00152       texture_ = Ogre::TextureManager::getSingleton().createManual(
00153         texture_name,        // name
00154         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00155         Ogre::TEX_TYPE_2D,   // type
00156         width, height,   // width & height of the render window 
00157         0,                   // number of mipmaps
00158         Ogre::PF_A8R8G8B8,   // pixel format chosen to match a format Qt can use
00159         Ogre::TU_DEFAULT     // usage
00160         );
00161       panel_material_->getTechnique(0)->getPass(0)
00162         ->createTextureUnitState(texture_name);
00163         
00164       panel_material_->getTechnique(0)->getPass(0)
00165         ->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00166     }
00167   }
00168 
00169   ScopedPixelBuffer OverlayObject::getBuffer()
00170   {
00171     if (isTextureReady()) {
00172       return ScopedPixelBuffer(texture_->getBuffer());
00173     }
00174     else {
00175       return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr());
00176     }
00177   }
00178 
00179   void OverlayObject::setPosition(double left, double top)
00180   {
00181     panel_->setPosition(left, top);
00182   }
00183 
00184   void OverlayObject::setDimensions(double width, double height)
00185   {
00186     panel_->setDimensions(width, height);
00187   }
00188 
00189   bool OverlayObject::isVisible()
00190   {
00191     return overlay_->isVisible();
00192   }
00193 
00194   unsigned int OverlayObject::getTextureWidth()
00195   {
00196     if (isTextureReady()) {
00197       return texture_->getWidth();
00198     }
00199     else {
00200       return 0;
00201     }
00202   }
00203 
00204   unsigned int OverlayObject::getTextureHeight()
00205   {
00206     if (isTextureReady()) {
00207       return texture_->getHeight();
00208     }
00209     else {
00210       return 0;
00211     }
00212   }
00213 
00214   
00215 }


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44