camera_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 <boost/bind.hpp>
00031 
00032 #include <OGRE/OgreManualObject.h>
00033 #include <OGRE/OgreMaterialManager.h>
00034 #include <OGRE/OgreRectangle2D.h>
00035 #include <OGRE/OgreRenderSystem.h>
00036 #include <OGRE/OgreRenderWindow.h>
00037 #include <OGRE/OgreSceneManager.h>
00038 #include <OGRE/OgreSceneNode.h>
00039 #include <OGRE/OgreTextureManager.h>
00040 #include <OGRE/OgreViewport.h>
00041 
00042 #include <tf/transform_listener.h>
00043 
00044 #include "rviz/bit_allocator.h"
00045 #include "rviz/frame_manager.h"
00046 #include "rviz/ogre_helpers/axes.h"
00047 #include "rviz/properties/enum_property.h"
00048 #include "rviz/properties/float_property.h"
00049 #include "rviz/properties/int_property.h"
00050 #include "rviz/properties/ros_topic_property.h"
00051 #include "rviz/render_panel.h"
00052 #include "rviz/uniform_string_stream.h"
00053 #include "rviz/validate_floats.h"
00054 #include "rviz/display_context.h"
00055 #include "rviz/properties/display_group_visibility_property.h"
00056 #include "rviz/load_resource.h"
00057 
00058 #include <image_transport/camera_common.h>
00059 
00060 #include "camera_display.h"
00061 
00062 namespace rviz
00063 {
00064 
00065 const QString CameraDisplay::BACKGROUND( "background" );
00066 const QString CameraDisplay::OVERLAY( "overlay" );
00067 const QString CameraDisplay::BOTH( "background and overlay" );
00068 
00069 bool validateFloats(const sensor_msgs::CameraInfo& msg)
00070 {
00071   bool valid = true;
00072   valid = valid && validateFloats( msg.D );
00073   valid = valid && validateFloats( msg.K );
00074   valid = valid && validateFloats( msg.R );
00075   valid = valid && validateFloats( msg.P );
00076   return valid;
00077 }
00078 
00079 CameraDisplay::CameraDisplay()
00080   : ImageDisplayBase()
00081   , texture_()
00082   , render_panel_( 0 )
00083   , caminfo_tf_filter_( 0 )
00084   , new_caminfo_( false )
00085   , force_render_( false )
00086   , caminfo_ok_(false)
00087 {
00088   image_position_property_ = new EnumProperty( "Image Rendering", BOTH,
00089                                                "Render the image behind all other geometry or overlay it on top, or both.",
00090                                                this, SLOT( forceRender() ));
00091   image_position_property_->addOption( BACKGROUND );
00092   image_position_property_->addOption( OVERLAY );
00093   image_position_property_->addOption( BOTH );
00094 
00095   alpha_property_ = new FloatProperty( "Overlay Alpha", 0.5,
00096                                        "The amount of transparency to apply to the camera image when rendered as overlay.",
00097                                        this, SLOT( updateAlpha() ));
00098   alpha_property_->setMin( 0 );
00099   alpha_property_->setMax( 1 );
00100 
00101   zoom_property_ = new FloatProperty( "Zoom Factor", 1.0,
00102                                       "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
00103                                       this, SLOT( forceRender() ));
00104   zoom_property_->setMin( 0.00001 );
00105   zoom_property_->setMax( 100000 );
00106 }
00107 
00108 CameraDisplay::~CameraDisplay()
00109 {
00110   render_panel_->getRenderWindow()->removeListener( this );
00111 
00112   unsubscribe();
00113   caminfo_tf_filter_->clear();
00114 
00115 
00116   //workaround. delete results in a later crash
00117   render_panel_->hide();
00118   //delete render_panel_;
00119 
00120   delete bg_screen_rect_;
00121   delete fg_screen_rect_;
00122 
00123   bg_scene_node_->getParentSceneNode()->removeAndDestroyChild( bg_scene_node_->getName() );
00124   fg_scene_node_->getParentSceneNode()->removeAndDestroyChild( fg_scene_node_->getName() );
00125 
00126   delete caminfo_tf_filter_;
00127 
00128   context_->visibilityBits()->freeBits(vis_bit_);
00129 }
00130 
00131 void CameraDisplay::onInitialize()
00132 {
00133   caminfo_tf_filter_ = new tf::MessageFilter<sensor_msgs::CameraInfo>( *context_->getTFClient(), fixed_frame_.toStdString(),
00134                                                                        queue_size_property_->getInt(), update_nh_ );
00135 
00136   bg_scene_node_ = scene_node_->createChildSceneNode();
00137   fg_scene_node_ = scene_node_->createChildSceneNode();
00138 
00139   {
00140     static int count = 0;
00141     UniformStringStream ss;
00142     ss << "CameraDisplayObject" << count++;
00143 
00144     //background rectangle
00145     bg_screen_rect_ = new Ogre::Rectangle2D(true);
00146     bg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00147 
00148     ss << "Material";
00149     bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00150     bg_material_->setDepthWriteEnabled(false);
00151 
00152     bg_material_->setReceiveShadows(false);
00153     bg_material_->setDepthCheckEnabled(false);
00154 
00155     bg_material_->getTechnique(0)->setLightingEnabled(false);
00156     Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
00157     tu->setTextureName(texture_.getTexture()->getName());
00158     tu->setTextureFiltering( Ogre::TFO_NONE );
00159     tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
00160 
00161     bg_material_->setCullingMode(Ogre::CULL_NONE);
00162     bg_material_->setSceneBlending( Ogre::SBT_REPLACE );
00163 
00164     Ogre::AxisAlignedBox aabInf;
00165     aabInf.setInfinite();
00166 
00167     bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
00168     bg_screen_rect_->setBoundingBox(aabInf);
00169     bg_screen_rect_->setMaterial(bg_material_->getName());
00170 
00171     bg_scene_node_->attachObject(bg_screen_rect_);
00172     bg_scene_node_->setVisible(false);
00173 
00174     //overlay rectangle
00175     fg_screen_rect_ = new Ogre::Rectangle2D(true);
00176     fg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
00177 
00178     fg_material_ = bg_material_->clone( ss.str()+"fg" );
00179     fg_screen_rect_->setBoundingBox(aabInf);
00180     fg_screen_rect_->setMaterial(fg_material_->getName());
00181 
00182     fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00183     fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00184 
00185     fg_scene_node_->attachObject(fg_screen_rect_);
00186     fg_scene_node_->setVisible(false);
00187   }
00188 
00189   updateAlpha();
00190 
00191   render_panel_ = new RenderPanel();
00192   render_panel_->getRenderWindow()->addListener( this );
00193   render_panel_->getRenderWindow()->setAutoUpdated(false);
00194   render_panel_->getRenderWindow()->setActive( false );
00195   render_panel_->resize( 640, 480 );
00196   render_panel_->initialize( context_->getSceneManager(), context_ );
00197 
00198   setAssociatedWidget( render_panel_ );
00199 
00200   render_panel_->setAutoRender(false);
00201   render_panel_->setOverlaysEnabled(false);
00202   render_panel_->getCamera()->setNearClipDistance( 0.01f );
00203 
00204   caminfo_tf_filter_->connectInput(caminfo_sub_);
00205   caminfo_tf_filter_->registerCallback(boost::bind(&CameraDisplay::caminfoCallback, this, _1));
00206   //context_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
00207 
00208   vis_bit_ = context_->visibilityBits()->allocBit();
00209   render_panel_->getViewport()->setVisibilityMask( vis_bit_ );
00210 
00211   visibility_property_ = new DisplayGroupVisibilityProperty(
00212       vis_bit_, context_->getRootDisplayGroup(), this, "Visibility", true,
00213       "Changes the visibility of other Displays in the camera view.");
00214 
00215   visibility_property_->setIcon( loadPixmap("package://rviz/icons/visibility.svg",true) );
00216 
00217   this->addChild( visibility_property_, 0 );
00218 }
00219 
00220 void CameraDisplay::preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00221 {
00222   QString image_position = image_position_property_->getString();
00223   bg_scene_node_->setVisible( caminfo_ok_ && (image_position == BACKGROUND || image_position == BOTH) );
00224   fg_scene_node_->setVisible( caminfo_ok_ && (image_position == OVERLAY || image_position == BOTH) );
00225 
00226   // set view flags on all displays
00227   visibility_property_->update();
00228 }
00229 
00230 void CameraDisplay::postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00231 {
00232   bg_scene_node_->setVisible( false );
00233   fg_scene_node_->setVisible( false );
00234 }
00235 
00236 void CameraDisplay::onEnable()
00237 {
00238   subscribe();
00239   render_panel_->getRenderWindow()->setActive(true);
00240 }
00241 
00242 void CameraDisplay::onDisable()
00243 {
00244   render_panel_->getRenderWindow()->setActive(false);
00245   unsubscribe();
00246   clear();
00247 }
00248 
00249 void CameraDisplay::subscribe()
00250 {
00251   if ( (!isEnabled()) || (topic_property_->getTopicStd().empty()) )
00252   {
00253     return;
00254   }
00255 
00256   std::string target_frame = fixed_frame_.toStdString();
00257   ImageDisplayBase::enableTFFilter(target_frame);
00258 
00259   ImageDisplayBase::subscribe();
00260 
00261   std::string topic = topic_property_->getTopicStd();
00262   std::string caminfo_topic = image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
00263 
00264   try
00265   {
00266     caminfo_sub_.subscribe( update_nh_, caminfo_topic, 1 );
00267     setStatus( StatusProperty::Ok, "Camera Info", "OK" );
00268   }
00269   catch( ros::Exception& e )
00270   {
00271     setStatus( StatusProperty::Error, "Camera Info", QString( "Error subscribing: ") + e.what() );
00272   }
00273 }
00274 
00275 void CameraDisplay::unsubscribe()
00276 {
00277   ImageDisplayBase::unsubscribe();
00278   caminfo_sub_.unsubscribe();
00279 }
00280 
00281 void CameraDisplay::updateAlpha()
00282 {
00283   float alpha = alpha_property_->getFloat();
00284 
00285   Ogre::Pass* pass = fg_material_->getTechnique( 0 )->getPass( 0 );
00286   if( pass->getNumTextureUnitStates() > 0 )
00287   {
00288     Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState( 0 );
00289     tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
00290   }
00291   else
00292   {
00293     fg_material_->setAmbient( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
00294     fg_material_->setDiffuse( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
00295   }
00296 
00297   force_render_ = true;
00298   context_->queueRender();
00299 }
00300 
00301 void CameraDisplay::forceRender()
00302 {
00303   force_render_ = true;
00304   context_->queueRender();
00305 }
00306 
00307 void CameraDisplay::updateQueueSize()
00308 {
00309   caminfo_tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00310   ImageDisplayBase::updateQueueSize();
00311 }
00312 
00313 void CameraDisplay::clear()
00314 {
00315   texture_.clear();
00316   force_render_ = true;
00317   context_->queueRender();
00318 
00319   new_caminfo_ = false;
00320   current_caminfo_.reset();
00321 
00322   setStatus( StatusProperty::Warn, "Camera Info",
00323              "No CameraInfo received on [" + QString::fromStdString( caminfo_sub_.getTopic() ) + "].  Topic may not exist.");
00324   setStatus( StatusProperty::Warn, "Image", "No Image received");
00325 
00326   render_panel_->getCamera()->setPosition( Ogre::Vector3( 999999, 999999, 999999 ));
00327 }
00328 
00329 void CameraDisplay::update( float wall_dt, float ros_dt )
00330 {
00331   try
00332   {
00333     if( texture_.update() || force_render_ )
00334     {
00335       caminfo_ok_ = updateCamera();
00336       force_render_ = false;
00337     }
00338   }
00339   catch( UnsupportedImageEncoding& e )
00340   {
00341     setStatus( StatusProperty::Error, "Image", e.what() );
00342   }
00343 
00344   render_panel_->getRenderWindow()->update();
00345 }
00346 
00347 bool CameraDisplay::updateCamera()
00348 {
00349   sensor_msgs::CameraInfo::ConstPtr info;
00350   sensor_msgs::Image::ConstPtr image;
00351   {
00352     boost::mutex::scoped_lock lock( caminfo_mutex_ );
00353 
00354     info = current_caminfo_;
00355     image = texture_.getImage();
00356   }
00357 
00358   if( !info || !image )
00359   {
00360     return false;
00361   }
00362 
00363   if( !validateFloats( *info ))
00364   {
00365     setStatus( StatusProperty::Error, "Camera Info", "Contains invalid floating point values (nans or infs)" );
00366     return false;
00367   }
00368 
00369   // if we're in 'exact' time mode, only show image if the time is exactly right
00370   ros::Time rviz_time = context_->getFrameManager()->getTime();
00371   if ( context_->getFrameManager()->getSyncMode() == FrameManager::SyncExact &&
00372       rviz_time != image->header.stamp )
00373   {
00374     std::ostringstream s;
00375     s << "Time-syncing active and no image at timestamp " << rviz_time.toSec() << ".";
00376     setStatus( StatusProperty::Warn, "Time", s.str().c_str() );
00377     return false;
00378   }
00379 
00380   Ogre::Vector3 position;
00381   Ogre::Quaternion orientation;
00382   context_->getFrameManager()->getTransform( image->header.frame_id, image->header.stamp, position, orientation );
00383 
00384   //printf( "CameraDisplay:updateCamera(): pos = %.2f, %.2f, %.2f.\n", position.x, position.y, position.z );
00385 
00386   // convert vision (Z-forward) frame to ogre frame (Z-out)
00387   orientation = orientation * Ogre::Quaternion( Ogre::Degree( 180 ), Ogre::Vector3::UNIT_X );
00388 
00389   float img_width = info->width;
00390   float img_height = info->height;
00391 
00392   // If the image width is 0 due to a malformed caminfo, try to grab the width from the image.
00393   if( img_width == 0 )
00394   {
00395     ROS_DEBUG( "Malformed CameraInfo on camera [%s], width = 0", qPrintable( getName() ));
00396     img_width = texture_.getWidth();
00397   }
00398 
00399   if (img_height == 0)
00400   {
00401     ROS_DEBUG( "Malformed CameraInfo on camera [%s], height = 0", qPrintable( getName() ));
00402     img_height = texture_.getHeight();
00403   }
00404 
00405   if( img_height == 0.0 || img_width == 0.0 )
00406   {
00407     setStatus( StatusProperty::Error, "Camera Info",
00408                "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)" );
00409     return false;
00410   }
00411 
00412   double fx = info->P[0];
00413   double fy = info->P[5];
00414 
00415   float win_width = render_panel_->width();
00416   float win_height = render_panel_->height();
00417   float zoom_x = zoom_property_->getFloat();
00418   float zoom_y = zoom_x;
00419 
00420   // Preserve aspect ratio
00421   if( win_width != 0 && win_height != 0 )
00422   {
00423     float img_aspect = (img_width/fx) / (img_height/fy);
00424     float win_aspect = win_width / win_height;
00425 
00426     if ( img_aspect > win_aspect )
00427     {
00428       zoom_y = zoom_y / img_aspect * win_aspect;
00429     }
00430     else
00431     {
00432       zoom_x = zoom_x / win_aspect * img_aspect;
00433     }
00434   }
00435 
00436   // Add the camera's translation relative to the left camera (from P[3]);
00437   double tx = -1 * (info->P[3] / fx);
00438   Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
00439   position = position + (right * tx);
00440 
00441   double ty = -1 * (info->P[7] / fy);
00442   Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
00443   position = position + (down * ty);
00444 
00445   if( !validateFloats( position ))
00446   {
00447     setStatus( StatusProperty::Error, "Camera Info", "CameraInfo/P resulted in an invalid position calculation (nans or infs)" );
00448     return false;
00449   }
00450 
00451   render_panel_->getCamera()->setPosition( position );
00452   render_panel_->getCamera()->setOrientation( orientation );
00453 
00454   // calculate the projection matrix
00455   double cx = info->P[2];
00456   double cy = info->P[6];
00457 
00458   double far_plane = 100;
00459   double near_plane = 0.01;
00460 
00461   Ogre::Matrix4 proj_matrix;
00462   proj_matrix = Ogre::Matrix4::ZERO;
00463  
00464   proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
00465   proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
00466 
00467   proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
00468   proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
00469 
00470   proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
00471   proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
00472 
00473   proj_matrix[3][2]= -1;
00474 
00475   render_panel_->getCamera()->setCustomProjectionMatrix( true, proj_matrix );
00476 
00477   setStatus( StatusProperty::Ok, "Camera Info", "OK" );
00478 
00479 #if 0
00480   static Axes* debug_axes = new Axes(scene_manager_, 0, 0.2, 0.01);
00481   debug_axes->setPosition(position);
00482   debug_axes->setOrientation(orientation);
00483 #endif
00484 
00485   //adjust the image rectangles to fit the zoom & aspect ratio
00486   bg_screen_rect_->setCorners( -1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y );
00487   fg_screen_rect_->setCorners( -1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y );
00488 
00489   Ogre::AxisAlignedBox aabInf;
00490   aabInf.setInfinite();
00491   bg_screen_rect_->setBoundingBox( aabInf );
00492   fg_screen_rect_->setBoundingBox( aabInf );
00493 
00494   setStatus( StatusProperty::Ok, "Time", "ok" );
00495   setStatus( StatusProperty::Ok, "Camera Info", "ok" );
00496 
00497   return true;
00498 }
00499 
00500 void CameraDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
00501 {
00502   texture_.addMessage(msg);
00503 }
00504 
00505 void CameraDisplay::caminfoCallback( const sensor_msgs::CameraInfo::ConstPtr& msg )
00506 {
00507   boost::mutex::scoped_lock lock( caminfo_mutex_ );
00508   current_caminfo_ = msg;
00509   new_caminfo_ = true;
00510 }
00511 
00512 void CameraDisplay::fixedFrameChanged()
00513 {
00514   std::string targetFrame = fixed_frame_.toStdString();
00515   caminfo_tf_filter_->setTargetFrame(targetFrame);
00516   ImageDisplayBase::fixedFrameChanged();
00517 }
00518 
00519 void CameraDisplay::reset()
00520 {
00521   ImageDisplayBase::reset();
00522   clear();
00523 }
00524 
00525 } // namespace rviz
00526 
00527 #include <pluginlib/class_list_macros.h>
00528 PLUGINLIB_EXPORT_CLASS( rviz::CameraDisplay, rviz::Display )


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:35