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 JSK Lab 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 #include <ros/ros.h>
00038 
00039 namespace jsk_rviz_plugins
00040 {
00041   ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer):
00042     pixel_buffer_(pixel_buffer)
00043   {
00044     pixel_buffer_->lock( Ogre::HardwareBuffer::HBL_NORMAL );
00045   }
00046 
00047   ScopedPixelBuffer::~ScopedPixelBuffer()
00048   {
00049     pixel_buffer_->unlock();
00050   }
00051 
00052   Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer()
00053   {
00054     return pixel_buffer_;
00055   }
00056 
00057   QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height)
00058   {
00059     const Ogre::PixelBox& pixelBox = pixel_buffer_->getCurrentLock();
00060     Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
00061     memset(pDest, 0, width * height);
00062     return QImage(pDest, width, height, QImage::Format_ARGB32 );
00063   }
00064 
00065   QImage ScopedPixelBuffer::getQImage(
00066     unsigned int width, unsigned int height, QColor& bg_color)
00067   {
00068     QImage Hud = getQImage(width, height);
00069     for (unsigned int i = 0; i < width; i++) {
00070       for (unsigned int j = 0; j < height; j++) {
00071         Hud.setPixel(i, j, bg_color.rgba());
00072       }
00073     }
00074     return Hud;
00075   }
00076 
00077   QImage ScopedPixelBuffer::getQImage(OverlayObject& overlay)
00078   {
00079     return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight());
00080   }
00081   
00082   QImage ScopedPixelBuffer::getQImage(OverlayObject& overlay,
00083                                       QColor& bg_color)
00084   {
00085     return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(),
00086                      bg_color);
00087   }
00088   
00089   OverlayObject::OverlayObject(const std::string& name)
00090     : name_(name)
00091   {
00092     std::string material_name = name_ + "Material";
00093     Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr();
00094     overlay_ = mOverlayMgr->create(name_);
00095     panel_ = static_cast<Ogre::PanelOverlayElement*> (
00096       mOverlayMgr->createOverlayElement("Panel", name_ + "Panel"));
00097     panel_->setMetricsMode(Ogre::GMM_PIXELS);
00098     
00099     panel_material_
00100       = Ogre::MaterialManager::getSingleton().create(
00101         material_name,
00102         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00103     panel_->setMaterialName(panel_material_->getName());
00104     overlay_->add2D(panel_);
00105   }
00106 
00107   OverlayObject::~OverlayObject()
00108   {
00109     hide();
00110     panel_material_->unload();
00111     Ogre::MaterialManager::getSingleton().remove(panel_material_->getName());
00112     // Ogre::OverlayManager* mOverlayMgr = Ogre::OverlayManager::getSingletonPtr();
00113     // mOverlayMgr->destroyOverlayElement(panel_);
00114     //delete panel_;
00115     //delete overlay_;
00116   }
00117 
00118   std::string OverlayObject::getName()
00119   {
00120     return name_;
00121   }
00122 
00123   void OverlayObject::hide()
00124   {
00125     if (overlay_->isVisible()) {
00126       overlay_->hide();
00127     }
00128   }
00129 
00130   void OverlayObject::show()
00131   {
00132     if (!overlay_->isVisible()) {
00133       overlay_->show();
00134     }
00135   }
00136 
00137   bool OverlayObject::isTextureReady()
00138   {
00139     return !texture_.isNull();
00140   }
00141 
00142   bool OverlayObject::updateTextureSize(unsigned int width, unsigned int height)
00143   {
00144     const std::string texture_name = name_ + "Texture";
00145     if (width == 0) {
00146       ROS_WARN("[OverlayObject] width=0 is specified as texture size");
00147       width = 1;
00148     }
00149     if (height == 0) {
00150       ROS_WARN("[OverlayObject] height=0 is specified as texture size");
00151       height = 1;
00152     }
00153     if (!isTextureReady() ||
00154         ((width != texture_->getWidth()) ||
00155          (height != texture_->getHeight()))) {
00156       if (isTextureReady()) {
00157         Ogre::TextureManager::getSingleton().remove(texture_name);
00158         panel_material_->getTechnique(0)->getPass(0)
00159           ->removeAllTextureUnitStates();
00160       }
00161       texture_ = Ogre::TextureManager::getSingleton().createManual(
00162         texture_name,        // name
00163         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00164         Ogre::TEX_TYPE_2D,   // type
00165         width, height,   // width & height of the render window 
00166         0,                   // number of mipmaps
00167         Ogre::PF_A8R8G8B8,   // pixel format chosen to match a format Qt can use
00168         Ogre::TU_DEFAULT     // usage
00169         );
00170       panel_material_->getTechnique(0)->getPass(0)
00171         ->createTextureUnitState(texture_name);
00172         
00173       panel_material_->getTechnique(0)->getPass(0)
00174         ->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00175     }
00176   }
00177 
00178   ScopedPixelBuffer OverlayObject::getBuffer()
00179   {
00180     if (isTextureReady()) {
00181       return ScopedPixelBuffer(texture_->getBuffer());
00182     }
00183     else {
00184       return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr());
00185     }
00186   }
00187 
00188   void OverlayObject::setPosition(double left, double top)
00189   {
00190     panel_->setPosition(left, top);
00191   }
00192 
00193   void OverlayObject::setDimensions(double width, double height)
00194   {
00195     panel_->setDimensions(width, height);
00196   }
00197 
00198   bool OverlayObject::isVisible()
00199   {
00200     return overlay_->isVisible();
00201   }
00202 
00203   unsigned int OverlayObject::getTextureWidth()
00204   {
00205     if (isTextureReady()) {
00206       return texture_->getWidth();
00207     }
00208     else {
00209       return 0;
00210     }
00211   }
00212 
00213   unsigned int OverlayObject::getTextureHeight()
00214   {
00215     if (isTextureReady()) {
00216       return texture_->getHeight();
00217     }
00218     else {
00219       return 0;
00220     }
00221   }
00222 
00223   
00224 }


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22