image_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, 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 #include "image_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/render_panel.h"
00033 #include "rviz/properties/property.h"
00034 #include "rviz/properties/property_manager.h"
00035 #include "rviz/window_manager_interface.h"
00036 #include "rviz/frame_manager.h"
00037 #include "rviz/validate_floats.h"
00038 #include "rviz/panel_dock_widget.h"
00039 #include "rviz/display_wrapper.h"
00040 
00041 #include <tf/transform_listener.h>
00042 
00043 #include <boost/bind.hpp>
00044 
00045 #include <OGRE/OgreSceneNode.h>
00046 #include <OGRE/OgreSceneManager.h>
00047 #include <OGRE/OgreRectangle2D.h>
00048 #include <OGRE/OgreMaterialManager.h>
00049 #include <OGRE/OgreTextureManager.h>
00050 #include <OGRE/OgreViewport.h>
00051 #include <OGRE/OgreRenderWindow.h>
00052 #include <OGRE/OgreManualObject.h>
00053 #include <OGRE/OgreRoot.h>
00054 #include <OGRE/OgreRenderSystem.h>
00055 
00056 namespace rviz
00057 {
00058 
00059 ImageDisplay::ImageDisplay()
00060   : Display()
00061   , transport_("raw")
00062   , texture_(update_nh_)
00063   , panel_container_( 0 )
00064 {
00065 }
00066 
00067 void ImageDisplay::onInitialize()
00068 {
00069   {
00070     static uint32_t count = 0;
00071     std::stringstream ss;
00072     ss << "ImageDisplay" << count++;
00073     scene_manager_ = Ogre::Root::getSingleton().createSceneManager(Ogre::ST_GENERIC, ss.str());
00074   }
00075 
00076   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00077 
00078   {
00079     static int count = 0;
00080     std::stringstream ss;
00081     ss << "ImageDisplayObject" << count++;
00082 
00083     screen_rect_ = new Ogre::Rectangle2D(true);
00084     screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00085     screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00086 
00087     ss << "Material";
00088     material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00089     material_->setSceneBlending( Ogre::SBT_REPLACE );
00090     material_->setDepthWriteEnabled(false);
00091     material_->setReceiveShadows(false);
00092     material_->setDepthCheckEnabled(false);
00093 
00094     material_->getTechnique(0)->setLightingEnabled(false);
00095     Ogre::TextureUnitState* tu = material_->getTechnique(0)->getPass(0)->createTextureUnitState();
00096     tu->setTextureName(texture_.getTexture()->getName());
00097     tu->setTextureFiltering( Ogre::TFO_NONE );
00098 
00099     material_->setCullingMode(Ogre::CULL_NONE);
00100     Ogre::AxisAlignedBox aabInf;
00101     aabInf.setInfinite();
00102     screen_rect_->setBoundingBox(aabInf);
00103     screen_rect_->setMaterial(material_->getName());
00104     scene_node_->attachObject(screen_rect_);
00105   }
00106 
00107   render_panel_ = new RenderPanel();
00108   render_panel_->getRenderWindow()->setAutoUpdated(false);
00109   render_panel_->getRenderWindow()->setActive( false );
00110 
00111   render_panel_->resize( 640, 480 );
00112   render_panel_->initialize(scene_manager_, vis_manager_);
00113 
00114   WindowManagerInterface* wm = vis_manager_->getWindowManager();
00115   if (wm)
00116   {
00117     panel_container_ = wm->addPane(name_, render_panel_);
00118   }
00119   render_panel_->setAutoRender(false);
00120   render_panel_->setOverlaysEnabled(false);
00121   render_panel_->getCamera()->setNearClipDistance( 0.01f );
00122 
00123   if( panel_container_ )
00124   {
00125     connect( panel_container_, SIGNAL( visibilityChanged( bool ) ), this, SLOT( setWrapperEnabled( bool )));
00126   }
00127 }
00128 
00129 ImageDisplay::~ImageDisplay()
00130 {
00131   unsubscribe();
00132 
00133   if( render_panel_ )
00134   {
00135     if( panel_container_ )
00136     {
00137       delete panel_container_;
00138     }
00139     else
00140     {
00141       delete render_panel_;
00142     }
00143   }
00144 
00145   delete screen_rect_;
00146 
00147   scene_node_->getParentSceneNode()->removeAndDestroyChild(scene_node_->getName());
00148 }
00149 
00150 void ImageDisplay::setWrapperEnabled( bool enabled )
00151 {
00152   // Have to use the DisplayWrapper disable function so the checkbox
00153   // gets checked or unchecked, since it owns the "enabled" property.
00154   DisplayWrapper* wrapper = vis_manager_->getDisplayWrapper( this );
00155   if( wrapper != NULL )
00156   {
00157     wrapper->setEnabled( enabled );
00158   }
00159 }
00160 
00161 void ImageDisplay::onEnable()
00162 {
00163   subscribe();
00164 
00165   if( render_panel_->parentWidget() == 0 )
00166   {
00167     render_panel_->show();
00168   }
00169   else
00170   {
00171     panel_container_->show();
00172   }
00173 
00174   render_panel_->getRenderWindow()->setActive(true);
00175 }
00176 
00177 void ImageDisplay::onDisable()
00178 {
00179   render_panel_->getRenderWindow()->setActive(false);
00180 
00181   if( render_panel_->parentWidget() == 0 )
00182   {
00183     if( render_panel_->isVisible() )
00184     {
00185       render_panel_->hide();
00186     }
00187   }
00188   else
00189   {
00190     if( panel_container_->isVisible() )
00191     {
00192       panel_container_->close();
00193     }
00194   }
00195 
00196   unsubscribe();
00197 
00198   clear();
00199 }
00200 
00201 void ImageDisplay::subscribe()
00202 {
00203   if ( !isEnabled() )
00204   {
00205     return;
00206   }
00207 
00208   try
00209   {
00210     texture_.setTopic(topic_);
00211     setStatus(status_levels::Ok, "Topic", "OK");
00212   }
00213   catch (ros::Exception& e)
00214   {
00215     setStatus(status_levels::Error, "Topic", std::string("Error subscribing: ") + e.what());
00216   }
00217 }
00218 
00219 void ImageDisplay::unsubscribe()
00220 {
00221   texture_.setTopic("");
00222 }
00223 
00224 void ImageDisplay::setQueueSize( int size )
00225 {
00226   if( size != texture_.getQueueSize() )
00227   {
00228     texture_.setQueueSize( size );
00229     propertyChanged( queue_size_property_ );
00230   }
00231 }
00232 
00233 int ImageDisplay::getQueueSize()
00234 {
00235   return texture_.getQueueSize();
00236 }
00237 
00238 void ImageDisplay::setTopic( const std::string& topic )
00239 {
00240   unsubscribe();
00241 
00242   topic_ = topic;
00243   clear();
00244 
00245   subscribe();
00246 
00247   propertyChanged(topic_property_);
00248 }
00249 
00250 void ImageDisplay::setTransport(const std::string& transport)
00251 {
00252   transport_ = transport;
00253 
00254   texture_.setTransportType(transport);
00255 
00256   propertyChanged(transport_property_);
00257 }
00258 
00259 void ImageDisplay::clear()
00260 {
00261   texture_.clear();
00262 
00263   setStatus(status_levels::Warn, "Image", "No Image received");
00264 
00265   if( render_panel_->getCamera() )
00266   {
00267     render_panel_->getCamera()->setPosition(Ogre::Vector3(999999, 999999, 999999));
00268   }
00269 }
00270 
00271 void ImageDisplay::updateStatus()
00272 {
00273   if (texture_.getImageCount() == 0)
00274   {
00275     setStatus(status_levels::Warn, "Image", "No image received");
00276   }
00277   else
00278   {
00279     std::stringstream ss;
00280     ss << texture_.getImageCount() << " images received";
00281     setStatus(status_levels::Ok, "Image", ss.str());
00282   }
00283 }
00284 
00285 void ImageDisplay::update(float wall_dt, float ros_dt)
00286 {
00287   updateStatus();
00288 
00289   try
00290   {
00291     texture_.update();
00292 
00293     //make sure the aspect ratio of the image is preserved
00294     float win_width = render_panel_->width();
00295     float win_height = render_panel_->height();
00296 
00297     float img_width = texture_.getWidth();
00298     float img_height = texture_.getHeight();
00299 
00300     if ( img_width != 0 && img_height != 0 && win_width !=0 && win_height != 0 )
00301     {
00302       float img_aspect = img_width / img_height;
00303       float win_aspect = win_width / win_height;
00304 
00305       if ( img_aspect > win_aspect )
00306       {
00307         screen_rect_->setCorners(-1.0f, 1.0f * win_aspect/img_aspect, 1.0f, -1.0f * win_aspect/img_aspect, false);
00308       }
00309       else
00310       {
00311         screen_rect_->setCorners(-1.0f * img_aspect/win_aspect, 1.0f, 1.0f * img_aspect/win_aspect, -1.0f, false);
00312       }
00313     }
00314 
00315     render_panel_->getRenderWindow()->update();
00316   }
00317   catch (UnsupportedImageEncoding& e)
00318   {
00319     setStatus(status_levels::Error, "Image", e.what());
00320   }
00321 }
00322 
00323 void ImageDisplay::onTransportEnumOptions(V_string& choices)
00324 {
00325   texture_.getAvailableTransportTypes(choices);
00326 }
00327 
00328 void ImageDisplay::createProperties()
00329 {
00330   topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Image Topic", property_prefix_, boost::bind( &ImageDisplay::getTopic, this ),
00331                                                                          boost::bind( &ImageDisplay::setTopic, this, _1 ), parent_category_, this );
00332   setPropertyHelpText(topic_property_, "sensor_msgs::Image topic to subscribe to.");
00333   ROSTopicStringPropertyPtr topic_prop = topic_property_.lock();
00334   topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::Image>());
00335 
00336   transport_property_ = property_manager_->createProperty<EditEnumProperty>("Transport Hint", property_prefix_, boost::bind(&ImageDisplay::getTransport, this),
00337                                                                             boost::bind(&ImageDisplay::setTransport, this, _1), parent_category_, this);
00338   EditEnumPropertyPtr ee_prop = transport_property_.lock();
00339   ee_prop->setOptionCallback(boost::bind(&ImageDisplay::onTransportEnumOptions, this, _1));
00340 
00341   queue_size_property_ = property_manager_->createProperty<IntProperty>( "Queue Size", property_prefix_,
00342                                                                          boost::bind( &ImageDisplay::getQueueSize, this ),
00343                                                                          boost::bind( &ImageDisplay::setQueueSize, this, _1 ),
00344                                                                          parent_category_, this );
00345   setPropertyHelpText( queue_size_property_, "Advanced: set the size of the incoming Image message queue.  Increasing this is useful if your incoming TF data is delayed significantly from your Image data, but it can greatly increase memory usage if the messages are big." );
00346 }
00347 
00348 void ImageDisplay::reset()
00349 {
00350   Display::reset();
00351 
00352   clear();
00353 }
00354 
00355 } // namespace rviz


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32