awesome_camera_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Note: this is a modified version of the RViz camera display and
00003  * intended to be included in RViz once it's finished.
00004  */
00005 
00006 /*
00007  * Copyright (c) 2012, Willow Garage, Inc.
00008  * All rights reserved.
00009  *
00010  * Redistribution and use in source and binary forms, with or without
00011  * modification, are permitted provided that the following conditions are met:
00012  *
00013  *     * Redistributions of source code must retain the above copyright
00014  *       notice, this list of conditions and the following disclaimer.
00015  *     * Redistributions in binary form must reproduce the above copyright
00016  *       notice, this list of conditions and the following disclaimer in the
00017  *       documentation and/or other materials provided with the distribution.
00018  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00019  *       contributors may be used to endorse or promote products derived from
00020  *       this software without specific prior written permission.
00021  *
00022  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00023  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00024  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00025  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00026  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00027  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00028  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00029  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00030  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00031  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  * POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include <boost/bind.hpp>
00036 
00037 #include <OGRE/OgreCamera.h>
00038 #include <OGRE/OgreManualObject.h>
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include <OGRE/OgreRenderSystem.h>
00041 #include <OGRE/OgreRenderWindow.h>
00042 #include <OGRE/OgreSceneManager.h>
00043 #include <OGRE/OgreSceneNode.h>
00044 #include <OGRE/OgreTextureManager.h>
00045 #include <OGRE/OgreViewport.h>
00046 #include <OGRE/OgreRectangle.h>
00047 #include <OGRE/OgreManualObject.h>
00048 #include <OGRE/OgreRenderOperation.h>
00049 
00050 
00051 #include <tf/transform_listener.h>
00052 
00053 #include "rviz/bit_allocator.h"
00054 #include "rviz/frame_manager.h"
00055 #include "rviz/ogre_helpers/axes.h"
00056 #include "rviz/properties/enum_property.h"
00057 #include "rviz/properties/float_property.h"
00058 #include "rviz/properties/int_property.h"
00059 #include "rviz/properties/ros_topic_property.h"
00060 #include "rviz/render_panel.h"
00061 #include "rviz/uniform_string_stream.h"
00062 #include "rviz/validate_floats.h"
00063 #include "rviz/display_context.h"
00064 #include "rviz/properties/display_group_visibility_property.h"
00065 #include "rviz/load_resource.h"
00066 #include "rviz/view_manager.h"
00067 #include "rviz/window_manager_interface.h"
00068 #include "rviz/panel_dock_widget.h"
00069 
00070 #include <image_transport/camera_common.h>
00071 
00072 #include "pr2_interactive_manipulation/awesome_camera_display.h"
00073 
00074 namespace rviz
00075 {
00076 
00077 const QString AwesomeCameraDisplay::BACKGROUND( "background" );
00078 const QString AwesomeCameraDisplay::OVERLAY( "overlay" );
00079 const QString AwesomeCameraDisplay::BOTH( "background and overlay" );
00080 
00081 bool validateFloats(const sensor_msgs::CameraInfo& msg)
00082 {
00083   bool valid = true;
00084   valid = valid && validateFloats( msg.D );
00085   valid = valid && validateFloats( msg.K );
00086   valid = valid && validateFloats( msg.R );
00087   valid = valid && validateFloats( msg.P );
00088   return valid;
00089 }
00090 
00091 void makeRect( std::string material_name, Ogre::ManualObject* rect )
00092 {
00093   rect->begin( material_name, Ogre::RenderOperation::OT_TRIANGLE_FAN );
00094   rect->position(      1.0,  1.0, -1.0 );
00095   rect->textureCoord(  1.0, 0.0 );
00096   rect->position(     -1.0, 1.0, -1.0 );
00097   rect->textureCoord( 0.0,  0.0 );
00098   rect->position(    -1.0, -1.0, -1.0 );
00099   rect->textureCoord( 0.0,  1.0 );
00100   rect->position(     1.0, -1.0, -1.0 );
00101   rect->textureCoord(  1.0,  1.0 );
00102   rect->end();
00103 }
00104 
00105 AwesomeCameraDisplay::AwesomeCameraDisplay()
00106   : ImageDisplayBase()
00107   , texture_()
00108   , caminfo_tf_filter_( 0 )
00109   , new_caminfo_( false )
00110   , render_panel_( 0 )
00111   , force_render_( false )
00112   , render_panel_dock_widget_(0)
00113 {
00114   show_panel_property_ = new BoolProperty( "Show Panel", true, "Show Extra Panel with the camera image, in addition to main view.",
00115                                            this, SLOT( showPanelPropertyChanged() ) );
00116 
00117   image_position_property_ = new EnumProperty( "Image Rendering", BOTH,
00118                                                "Render the image behind all other geometry or overlay it on top, or both.",
00119                                                this, SLOT( forceRender() ));
00120   image_position_property_->addOption( BACKGROUND );
00121   image_position_property_->addOption( OVERLAY );
00122   image_position_property_->addOption( BOTH );
00123 
00124   alpha_property_ = new FloatProperty( "Overlay Alpha", 0.5,
00125                                        "The amount of transparency to apply to the camera image when rendered as overlay.",
00126                                        this, SLOT( updateAlpha() ));
00127   alpha_property_->setMin( 0 );
00128   alpha_property_->setMax( 1 );
00129 
00130   zoom_property_ = new FloatProperty( "Zoom Factor", 1.0,
00131                                       "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
00132                                       this, SLOT( forceRender() ));
00133   zoom_property_->setMin( 0.00001 );
00134   zoom_property_->setMax( 100000 );
00135 
00136   near_clip_property_ = new FloatProperty( "Near Clip Distance", 0.01f,
00137                                       "Anything closer to the camera that this threshold will not get rendered.",
00138                                       this, SLOT( forceRender() ));
00139   near_clip_property_->setMin( 0.0001 );
00140   near_clip_property_->setMax( 100000 );
00141 }
00142 
00143 AwesomeCameraDisplay::~AwesomeCameraDisplay()
00144 {
00145   unsubscribe();
00146   caminfo_tf_filter_->clear();
00147 
00148   delete render_panel_;
00149   delete bg_screen_rect_;
00150   delete fg_screen_rect_;
00151 
00152   bg_scene_node_->getParentSceneNode()->removeAndDestroyChild( bg_scene_node_->getName() );
00153   fg_scene_node_->getParentSceneNode()->removeAndDestroyChild( fg_scene_node_->getName() );
00154 
00155   delete caminfo_tf_filter_;
00156 
00157   context_->visibilityBits()->freeBits(vis_bit_);
00158 }
00159 
00160 void AwesomeCameraDisplay::onInitialize()
00161 {
00162   caminfo_tf_filter_ = new tf::MessageFilter<sensor_msgs::CameraInfo>( *context_->getTFClient(), fixed_frame_.toStdString(),
00163                                                                        queue_size_property_->getInt(), update_nh_ );
00164 
00165   bg_scene_node_ = scene_node_->createChildSceneNode();
00166   fg_scene_node_ = scene_node_->createChildSceneNode();
00167 
00168   {
00169     static int count = 0;
00170     UniformStringStream ss;
00171     ss << "CameraDisplayRect" << count++;
00172 
00173     // image texture material
00174     ss << "Material";
00175     bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
00176     bg_material_->setDepthWriteEnabled(false);
00177     bg_material_->setDepthCheckEnabled(false);
00178     bg_material_->setReceiveShadows(false);
00179 
00180     bg_material_->getTechnique(0)->setLightingEnabled(false);
00181     Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
00182     tu->setTextureName(texture_.getTexture()->getName());
00183     tu->setTextureFiltering( Ogre::TFO_NONE );
00184     tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
00185 
00186     bg_material_->setCullingMode(Ogre::CULL_NONE);
00187     bg_material_->setSceneBlending( Ogre::SBT_REPLACE );
00188 
00189     //background rectangle
00190     bg_screen_rect_ = new Ogre::ManualObject(ss.str()+"_bg");
00191     makeRect( bg_material_->getName(), bg_screen_rect_ );
00192     bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
00193 
00194     bg_scene_node_->attachObject(bg_screen_rect_);
00195     bg_scene_node_->setVisible(false);
00196 
00197     //overlay rectangle
00198     fg_material_ = bg_material_->clone( ss.str()+"fg" );
00199     fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
00200 
00201     fg_screen_rect_ = new Ogre::ManualObject(ss.str()+"_fg");
00202     makeRect( fg_material_->getName(), fg_screen_rect_ );
00203     fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
00204 
00205     fg_scene_node_->attachObject(fg_screen_rect_);
00206     fg_scene_node_->setVisible(false);
00207   }
00208 
00209   updateAlpha();
00210 
00211   // we need to listen to the main window rendering so we can fiddle with its visibility bits
00212   context_->getViewManager()->getRenderPanel()->getRenderWindow()->addListener(this);
00213 
00214   render_panel_ = new RenderPanel();
00215   render_panel_->getRenderWindow()->addListener( this );
00216   render_panel_->getRenderWindow()->setAutoUpdated(false);
00217   render_panel_->getRenderWindow()->setActive( false );
00218   render_panel_->resize( 640, 480 );
00219   render_panel_->initialize( context_->getSceneManager(), context_ );
00220 
00221   //setAssociatedWidget( render_panel_ );
00222 
00223   WindowManagerInterface* wm = context_->getWindowManager();
00224   if( wm )
00225   {
00226     render_panel_dock_widget_ = wm->addPane( getName(), render_panel_ );
00227     connect( render_panel_dock_widget_, SIGNAL( visibilityChanged( bool ) ), this, SLOT( panelVisibilityChanged( bool )));
00228     render_panel_dock_widget_->setIcon( getIcon() );
00229   }
00230 
00231   render_panel_->setAutoRender(false);
00232   render_panel_->setOverlaysEnabled(false);
00233   render_panel_->getCamera()->setNearClipDistance( 0.01f );
00234 
00235   caminfo_tf_filter_->connectInput(caminfo_sub_);
00236   caminfo_tf_filter_->registerCallback(boost::bind(&AwesomeCameraDisplay::caminfoCallback, this, _1));
00237   context_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
00238 
00239   vis_bit_ = context_->visibilityBits()->allocBit();
00240   render_panel_->getViewport()->setVisibilityMask( vis_bit_ );
00241 
00242   visibility_property_ = new DisplayGroupVisibilityProperty(
00243       vis_bit_, context_->getRootDisplayGroup(), this, "Visibility", true,
00244       "Changes the visibility of other Displays in the camera view.");
00245 
00246   visibility_property_->setIcon( loadPixmap("package://rviz/icons/visibility.svg",true) );
00247 
00248   this->addChild( visibility_property_, 0 );
00249 }
00250 
00251 void AwesomeCameraDisplay::panelVisibilityChanged( bool visible )
00252 {
00253   show_panel_property_->setBool(visible);
00254 }
00255 
00256 void AwesomeCameraDisplay::showPanelPropertyChanged()
00257 {
00258   if ( render_panel_dock_widget_ )
00259   {
00260     render_panel_dock_widget_->setVisible( show_panel_property_->getBool() );
00261   }
00262 }
00263 
00264 void AwesomeCameraDisplay::preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00265 {
00266   //determine if the main view sits inside the camera
00267   Ogre::Camera* main_cam = context_->getViewManager()->getCurrent()->getCamera();
00268   Ogre::Camera* my_cam = render_panel_->getCamera();
00269   float dist = (main_cam->getDerivedPosition() - my_cam->getDerivedPosition()).length();
00270 
00271   Ogre::Viewport* vp = evt.source->getViewport(0);
00272   if ( vp == render_panel_->getViewport() || dist < 0.02 )
00273   {
00274     vp->setVisibilityMask( vis_bit_ );
00275     QString image_position = image_position_property_->getString();
00276     bg_scene_node_->setVisible( image_position == BACKGROUND || image_position == BOTH );
00277     fg_scene_node_->setVisible( image_position == OVERLAY || image_position == BOTH );
00278   }
00279   else
00280   {
00281     vp->setVisibilityMask( 0xffffffff );
00282     bg_scene_node_->setVisible( false );
00283     fg_scene_node_->setVisible( false );
00284   }
00285 
00286   // apply visibility bit to all other displays
00287   visibility_property_->update();
00288 }
00289 
00290 void AwesomeCameraDisplay::postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
00291 {
00292   Ogre::Viewport* vp = evt.source->getViewport(0);
00293   vp->setVisibilityMask( 0xffffffff );
00294   bg_scene_node_->setVisible( false );
00295   fg_scene_node_->setVisible( false );
00296 }
00297 
00298 void AwesomeCameraDisplay::onEnable()
00299 {
00300   subscribe();
00301   render_panel_->getRenderWindow()->setActive(true);
00302 }
00303 
00304 void AwesomeCameraDisplay::onDisable()
00305 {
00306   render_panel_->getRenderWindow()->setActive(false);
00307   unsubscribe();
00308   clear();
00309 }
00310 
00311 void AwesomeCameraDisplay::subscribe()
00312 {
00313   if ( (!isEnabled()) || (topic_property_->getTopicStd().empty()) )
00314   {
00315     return;
00316   }
00317 
00318   std::string target_frame = fixed_frame_.toStdString();
00319   ImageDisplayBase::enableTFFilter(target_frame);
00320 
00321   ImageDisplayBase::subscribe();
00322 
00323   std::string topic = topic_property_->getTopicStd();
00324   std::string caminfo_topic = image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
00325 
00326   try
00327   {
00328     caminfo_sub_.subscribe( update_nh_, caminfo_topic, 1 );
00329     setStatus( StatusProperty::Ok, "Camera Info", "OK" );
00330   }
00331   catch( ros::Exception& e )
00332   {
00333     setStatus( StatusProperty::Error, "Camera Info", QString( "Error subscribing: ") + e.what() );
00334   }
00335 }
00336 
00337 void AwesomeCameraDisplay::unsubscribe()
00338 {
00339   ImageDisplayBase::unsubscribe();
00340   caminfo_sub_.unsubscribe();
00341 }
00342 
00343 void AwesomeCameraDisplay::updateAlpha()
00344 {
00345   float alpha = alpha_property_->getFloat();
00346 
00347   Ogre::Pass* pass = fg_material_->getTechnique( 0 )->getPass( 0 );
00348   if( pass->getNumTextureUnitStates() > 0 )
00349   {
00350     Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState( 0 );
00351     tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
00352   }
00353   else
00354   {
00355     fg_material_->setAmbient( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
00356     fg_material_->setDiffuse( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
00357   }
00358 
00359   force_render_ = true;
00360   context_->queueRender();
00361 }
00362 
00363 void AwesomeCameraDisplay::forceRender()
00364 {
00365   force_render_ = true;
00366   context_->queueRender();
00367 }
00368 
00369 void AwesomeCameraDisplay::updateQueueSize()
00370 {
00371   caminfo_tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00372   ImageDisplayBase::updateQueueSize();
00373 }
00374 
00375 void AwesomeCameraDisplay::clear()
00376 {
00377   texture_.clear();
00378   force_render_ = true;
00379   context_->queueRender();
00380 
00381   new_caminfo_ = false;
00382   current_caminfo_.reset();
00383 
00384   setStatus( StatusProperty::Warn, "Camera Info",
00385              "No CameraInfo received on [" + QString::fromStdString( caminfo_sub_.getTopic() ) + "].  Topic may not exist.");
00386   setStatus( StatusProperty::Warn, "Image", "No Image received");
00387 
00388   render_panel_->getCamera()->setPosition( Ogre::Vector3( 999999, 999999, 999999 ));
00389 }
00390 
00391 void AwesomeCameraDisplay::update( float wall_dt, float ros_dt )
00392 {
00393   try
00394   {
00395     if( texture_.update() || force_render_ )
00396     {
00397       updateCamera();
00398       force_render_ = false;
00399     }
00400   }
00401   catch( UnsupportedImageEncoding& e )
00402   {
00403     setStatus( StatusProperty::Error, "Image", e.what() );
00404   }
00405 
00406   render_panel_->getRenderWindow()->update();
00407 }
00408 
00409 void AwesomeCameraDisplay::updateCamera()
00410 {
00411   sensor_msgs::CameraInfo::ConstPtr info;
00412   sensor_msgs::Image::ConstPtr image;
00413   {
00414     boost::mutex::scoped_lock lock( caminfo_mutex_ );
00415 
00416     info = current_caminfo_;
00417     image = texture_.getImage();
00418   }
00419 
00420   if( !info || !image )
00421   {
00422     return;
00423   }
00424 
00425   if( !validateFloats( *info ))
00426   {
00427     setStatus( StatusProperty::Error, "Camera Info", "Contains invalid floating point values (nans or infs)" );
00428     return;
00429   }
00430 
00431   Ogre::Vector3 position;
00432   Ogre::Quaternion orientation;
00433   context_->getFrameManager()->getTransform( image->header.frame_id, ros::Time(0), position, orientation );
00434 
00435   //printf( "CameraDisplay:updateCamera(): pos = %.2f, %.2f, %.2f.\n", position.x, position.y, position.z );
00436 
00437   // convert vision (Z-forward) frame to ogre frame (Z-out)
00438   orientation = orientation * Ogre::Quaternion( Ogre::Degree( 180 ), Ogre::Vector3::UNIT_X );
00439 
00440   float img_width = info->width;
00441   float img_height = info->height;
00442 
00443   // If the image width is 0 due to a malformed caminfo, try to grab the width from the image.
00444   if( img_width == 0 )
00445   {
00446     ROS_DEBUG( "Malformed CameraInfo on camera [%s], width = 0", qPrintable( getName() ));
00447 
00448     img_width = texture_.getWidth();
00449   }
00450 
00451   if (img_height == 0)
00452   {
00453     ROS_DEBUG( "Malformed CameraInfo on camera [%s], height = 0", qPrintable( getName() ));
00454 
00455     img_height = texture_.getHeight();
00456   }
00457 
00458   if( img_height == 0.0 || img_width == 0.0 )
00459   {
00460     setStatus( StatusProperty::Error, "Camera Info",
00461                "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)" );
00462     return;
00463   }
00464 
00465   double fx = info->K[0];
00466   double fy = info->K[4];
00467 
00468   scene_node_->setScale( 0.5*img_width / fx, 0.5*img_height / fy, 1.0 );
00469 
00470   float win_width = render_panel_->width();
00471   float win_height = render_panel_->height();
00472   float zoom_x = zoom_property_->getFloat();
00473   float zoom_y = zoom_x;
00474 
00475   // Preserve aspect ratio
00476   if( win_width != 0 && win_height != 0 )
00477   {
00478     float img_aspect = (img_width/fx) / (img_height/fy);
00479     float win_aspect = win_width / win_height;
00480 
00481     if ( img_aspect > win_aspect )
00482     {
00483       zoom_y = zoom_y / img_aspect * win_aspect;
00484     }
00485     else
00486     {
00487       zoom_x = zoom_x / win_aspect * img_aspect;
00488     }
00489   }
00490 
00491   // Add the camera's translation relative to the left camera (from P[3]);
00492   double tx = -1 * (info->P[3] / fx);
00493   Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
00494   position = position + (right * tx);
00495 
00496   double ty = -1 * (info->P[7] / fy);
00497   Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
00498   position = position + (down * ty);
00499 
00500   if( !validateFloats( position ))
00501   {
00502     setStatus( StatusProperty::Error, "Camera Info", "CameraInfo/P resulted in an invalid position calculation (nans or infs)" );
00503     return;
00504   }
00505 
00506   render_panel_->getCamera()->setPosition( position );
00507   render_panel_->getCamera()->setOrientation( orientation );
00508 
00509   scene_node_->setPosition( position );
00510   scene_node_->setOrientation( orientation );
00511 
00512   // calculate the projection matrix
00513   double cx = info->P[2];
00514   double cy = info->P[6];
00515 
00516   double far_plane = 1000.0;
00517   double near_plane = near_clip_property_->getFloat();
00518 
00519   Ogre::Matrix4 proj_matrix;
00520   proj_matrix = Ogre::Matrix4::ZERO;
00521  
00522   proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
00523   proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
00524 
00525   proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
00526   proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
00527 
00528   proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
00529   proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
00530 
00531   proj_matrix[3][2]= -1;
00532 
00533   render_panel_->getCamera()->setCustomProjectionMatrix( true, proj_matrix );
00534 
00535   setStatus( StatusProperty::Ok, "Camera Info", "OK" );
00536 
00537 #if 0
00538   static Axes* debug_axes = new Axes(scene_manager_, 0, 0.2, 0.01);
00539   debug_axes->setPosition(position);
00540   debug_axes->setOrientation(orientation);
00541 #endif
00542 }
00543 
00544 void AwesomeCameraDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
00545 {
00546   texture_.addMessage(msg);
00547 }
00548 
00549 void AwesomeCameraDisplay::caminfoCallback( const sensor_msgs::CameraInfo::ConstPtr& msg )
00550 {
00551   boost::mutex::scoped_lock lock( caminfo_mutex_ );
00552   current_caminfo_ = msg;
00553   new_caminfo_ = true;
00554 }
00555 
00556 void AwesomeCameraDisplay::fixedFrameChanged()
00557 {
00558   std::string targetFrame = fixed_frame_.toStdString();
00559   caminfo_tf_filter_->setTargetFrame(targetFrame);
00560   ImageDisplayBase::fixedFrameChanged();
00561 }
00562 
00563 void AwesomeCameraDisplay::reset()
00564 {
00565   ImageDisplayBase::reset();
00566   clear();
00567 }
00568 
00569 } // namespace rviz


pr2_interactive_manipulation_frontend
Author(s): Jonathan Binney
autogenerated on Mon Oct 6 2014 12:06:28