camera_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <boost/bind.hpp>
31 
32 #include <OgreManualObject.h>
33 #include <OgreMaterialManager.h>
34 #include <OgreRectangle2D.h>
35 #include <OgreRenderSystem.h>
36 #include <OgreRenderWindow.h>
37 #include <OgreSceneManager.h>
38 #include <OgreSceneNode.h>
39 #include <OgreTextureManager.h>
40 #include <OgreViewport.h>
41 #include <OgreTechnique.h>
42 #include <OgreCamera.h>
43 
44 #include <tf/transform_listener.h>
45 
46 #include "rviz/bit_allocator.h"
47 #include "rviz/frame_manager.h"
48 #include "rviz/ogre_helpers/axes.h"
53 #include "rviz/render_panel.h"
55 #include "rviz/validate_floats.h"
56 #include "rviz/display_context.h"
58 #include "rviz/load_resource.h"
59 
61 
62 #include "camera_display.h"
63 
64 namespace rviz
65 {
66 
67 const QString CameraDisplay::BACKGROUND( "background" );
68 const QString CameraDisplay::OVERLAY( "overlay" );
69 const QString CameraDisplay::BOTH( "background and overlay" );
70 
71 bool validateFloats(const sensor_msgs::CameraInfo& msg)
72 {
73  bool valid = true;
74  valid = valid && validateFloats( msg.D );
75  valid = valid && validateFloats( msg.K );
76  valid = valid && validateFloats( msg.R );
77  valid = valid && validateFloats( msg.P );
78  return valid;
79 }
80 
83  , texture_()
84  , render_panel_( 0 )
85  , caminfo_tf_filter_( 0 )
86  , new_caminfo_( false )
87  , force_render_( false )
88  , caminfo_ok_(false)
89 {
90  image_position_property_ = new EnumProperty( "Image Rendering", BOTH,
91  "Render the image behind all other geometry or overlay it on top, or both.",
92  this, SLOT( forceRender() ));
96 
97  alpha_property_ = new FloatProperty( "Overlay Alpha", 0.5,
98  "The amount of transparency to apply to the camera image when rendered as overlay.",
99  this, SLOT( updateAlpha() ));
100  alpha_property_->setMin( 0 );
101  alpha_property_->setMax( 1 );
102 
103  zoom_property_ = new FloatProperty( "Zoom Factor", 1.0,
104  "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
105  this, SLOT( forceRender() ));
106  zoom_property_->setMin( 0.00001 );
107  zoom_property_->setMax( 100000 );
108 }
109 
111 {
112  if ( initialized() )
113  {
114  render_panel_->getRenderWindow()->removeListener( this );
115 
116  unsubscribe();
118 
119 
120  //workaround. delete results in a later crash
121  render_panel_->hide();
122  //delete render_panel_;
123 
124  delete bg_screen_rect_;
125  delete fg_screen_rect_;
126 
127  bg_scene_node_->getParentSceneNode()->removeAndDestroyChild( bg_scene_node_->getName() );
128  fg_scene_node_->getParentSceneNode()->removeAndDestroyChild( fg_scene_node_->getName() );
129 
130  delete caminfo_tf_filter_;
131 
133  }
134 }
135 
137 {
139 
142 
143  bg_scene_node_ = scene_node_->createChildSceneNode();
144  fg_scene_node_ = scene_node_->createChildSceneNode();
145 
146  {
147  static int count = 0;
149  ss << "CameraDisplayObject" << count++;
150 
151  //background rectangle
152  bg_screen_rect_ = new Ogre::Rectangle2D(true);
153  bg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
154 
155  ss << "Material";
156  bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
157  bg_material_->setDepthWriteEnabled(false);
158 
159  bg_material_->setReceiveShadows(false);
160  bg_material_->setDepthCheckEnabled(false);
161 
162  bg_material_->getTechnique(0)->setLightingEnabled(false);
163  Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
164  tu->setTextureName(texture_.getTexture()->getName());
165  tu->setTextureFiltering( Ogre::TFO_NONE );
166  tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
167 
168  bg_material_->setCullingMode(Ogre::CULL_NONE);
169  bg_material_->setSceneBlending( Ogre::SBT_REPLACE );
170 
171  Ogre::AxisAlignedBox aabInf;
172  aabInf.setInfinite();
173 
174  bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
175  bg_screen_rect_->setBoundingBox(aabInf);
176  bg_screen_rect_->setMaterial(bg_material_->getName());
177 
178  bg_scene_node_->attachObject(bg_screen_rect_);
179  bg_scene_node_->setVisible(false);
180 
181  //overlay rectangle
182  fg_screen_rect_ = new Ogre::Rectangle2D(true);
183  fg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
184 
185  fg_material_ = bg_material_->clone( ss.str()+"fg" );
186  fg_screen_rect_->setBoundingBox(aabInf);
187  fg_screen_rect_->setMaterial(fg_material_->getName());
188 
189  fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
190  fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
191 
192  fg_scene_node_->attachObject(fg_screen_rect_);
193  fg_scene_node_->setVisible(false);
194  }
195 
196  updateAlpha();
197 
198  render_panel_ = new RenderPanel();
199  render_panel_->getRenderWindow()->addListener( this );
200  render_panel_->getRenderWindow()->setAutoUpdated(false);
201  render_panel_->getRenderWindow()->setActive( false );
202  render_panel_->resize( 640, 480 );
204 
206 
209  render_panel_->getCamera()->setNearClipDistance( 0.01f );
210 
213  //context_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
214 
216  render_panel_->getViewport()->setVisibilityMask( vis_bit_ );
217 
219  vis_bit_, context_->getRootDisplayGroup(), this, "Visibility", true,
220  "Changes the visibility of other Displays in the camera view.");
221 
222  visibility_property_->setIcon( loadPixmap("package://rviz/icons/visibility.svg",true) );
223 
224  this->addChild( visibility_property_, 0 );
225 }
226 
227 void CameraDisplay::preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
228 {
229  QString image_position = image_position_property_->getString();
230  bg_scene_node_->setVisible( caminfo_ok_ && (image_position == BACKGROUND || image_position == BOTH) );
231  fg_scene_node_->setVisible( caminfo_ok_ && (image_position == OVERLAY || image_position == BOTH) );
232 
233  // set view flags on all displays
235 }
236 
237 void CameraDisplay::postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
238 {
239  bg_scene_node_->setVisible( false );
240  fg_scene_node_->setVisible( false );
241 }
242 
244 {
245  subscribe();
246  render_panel_->getRenderWindow()->setActive(true);
247 }
248 
250 {
251  render_panel_->getRenderWindow()->setActive(false);
252  unsubscribe();
253  clear();
254 }
255 
257 {
258  if ( (!isEnabled()) || (topic_property_->getTopicStd().empty()) )
259  {
260  return;
261  }
262 
263  std::string target_frame = fixed_frame_.toStdString();
264  ImageDisplayBase::enableTFFilter(target_frame);
265 
267 
268  std::string topic = topic_property_->getTopicStd();
269  std::string caminfo_topic = image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
270 
271  try
272  {
273  caminfo_sub_.subscribe( update_nh_, caminfo_topic, 1 );
274  setStatus( StatusProperty::Ok, "Camera Info", "OK" );
275  }
276  catch( ros::Exception& e )
277  {
278  setStatus( StatusProperty::Error, "Camera Info", QString( "Error subscribing: ") + e.what() );
279  }
280 }
281 
283 {
286 }
287 
289 {
290  float alpha = alpha_property_->getFloat();
291 
292  Ogre::Pass* pass = fg_material_->getTechnique( 0 )->getPass( 0 );
293  if( pass->getNumTextureUnitStates() > 0 )
294  {
295  Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState( 0 );
296  tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
297  }
298  else
299  {
300  fg_material_->setAmbient( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
301  fg_material_->setDiffuse( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
302  }
303 
304  force_render_ = true;
306 }
307 
309 {
310  force_render_ = true;
312 }
313 
315 {
318 }
319 
321 {
322  texture_.clear();
323  force_render_ = true;
325 
326  new_caminfo_ = false;
327  current_caminfo_.reset();
328 
329  setStatus( StatusProperty::Warn, "Camera Info",
330  "No CameraInfo received on [" + QString::fromStdString( caminfo_sub_.getTopic() ) + "]. Topic may not exist.");
331  setStatus( StatusProperty::Warn, "Image", "No Image received");
332 
333  render_panel_->getCamera()->setPosition( Ogre::Vector3( 999999, 999999, 999999 ));
334 }
335 
336 void CameraDisplay::update( float wall_dt, float ros_dt )
337 {
338  try
339  {
340  if( texture_.update() || force_render_ )
341  {
343  force_render_ = false;
344  }
345  }
346  catch( UnsupportedImageEncoding& e )
347  {
348  setStatus( StatusProperty::Error, "Image", e.what() );
349  }
350 
351  render_panel_->getRenderWindow()->update();
352 }
353 
355 {
356  sensor_msgs::CameraInfo::ConstPtr info;
357  sensor_msgs::Image::ConstPtr image;
358  {
359  boost::mutex::scoped_lock lock( caminfo_mutex_ );
360 
361  info = current_caminfo_;
362  image = texture_.getImage();
363  }
364 
365  if( !info || !image )
366  {
367  return false;
368  }
369 
370  if( !validateFloats( *info ))
371  {
372  setStatus( StatusProperty::Error, "Camera Info", "Contains invalid floating point values (nans or infs)" );
373  return false;
374  }
375 
376  // if we're in 'exact' time mode, only show image if the time is exactly right
377  ros::Time rviz_time = context_->getFrameManager()->getTime();
379  rviz_time != image->header.stamp )
380  {
381  std::ostringstream s;
382  s << "Time-syncing active and no image at timestamp " << rviz_time.toSec() << ".";
383  setStatus( StatusProperty::Warn, "Time", s.str().c_str() );
384  return false;
385  }
386 
387  Ogre::Vector3 position;
388  Ogre::Quaternion orientation;
389  context_->getFrameManager()->getTransform( image->header.frame_id, image->header.stamp, position, orientation );
390 
391  //printf( "CameraDisplay:updateCamera(): pos = %.2f, %.2f, %.2f.\n", position.x, position.y, position.z );
392 
393  // convert vision (Z-forward) frame to ogre frame (Z-out)
394  orientation = orientation * Ogre::Quaternion( Ogre::Degree( 180 ), Ogre::Vector3::UNIT_X );
395 
396  float img_width = info->width;
397  float img_height = info->height;
398 
399  // If the image width is 0 due to a malformed caminfo, try to grab the width from the image.
400  if( img_width == 0 )
401  {
402  ROS_DEBUG( "Malformed CameraInfo on camera [%s], width = 0", qPrintable( getName() ));
403  img_width = texture_.getWidth();
404  }
405 
406  if (img_height == 0)
407  {
408  ROS_DEBUG( "Malformed CameraInfo on camera [%s], height = 0", qPrintable( getName() ));
409  img_height = texture_.getHeight();
410  }
411 
412  if( img_height == 0.0 || img_width == 0.0 )
413  {
414  setStatus( StatusProperty::Error, "Camera Info",
415  "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)" );
416  return false;
417  }
418 
419  double fx = info->P[0];
420  double fy = info->P[5];
421 
422  float win_width = render_panel_->width();
423  float win_height = render_panel_->height();
424  float zoom_x = zoom_property_->getFloat();
425  float zoom_y = zoom_x;
426 
427  // Preserve aspect ratio
428  if( win_width != 0 && win_height != 0 )
429  {
430  float img_aspect = (img_width/fx) / (img_height/fy);
431  float win_aspect = win_width / win_height;
432 
433  if ( img_aspect > win_aspect )
434  {
435  zoom_y = zoom_y / img_aspect * win_aspect;
436  }
437  else
438  {
439  zoom_x = zoom_x / win_aspect * img_aspect;
440  }
441  }
442 
443  // Add the camera's translation relative to the left camera (from P[3]);
444  double tx = -1 * (info->P[3] / fx);
445  Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
446  position = position + (right * tx);
447 
448  double ty = -1 * (info->P[7] / fy);
449  Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
450  position = position + (down * ty);
451 
452  if( !validateFloats( position ))
453  {
454  setStatus( StatusProperty::Error, "Camera Info", "CameraInfo/P resulted in an invalid position calculation (nans or infs)" );
455  return false;
456  }
457 
458  render_panel_->getCamera()->setPosition( position );
459  render_panel_->getCamera()->setOrientation( orientation );
460 
461  // calculate the projection matrix
462  double cx = info->P[2];
463  double cy = info->P[6];
464 
465  double far_plane = 100;
466  double near_plane = 0.01;
467 
468  Ogre::Matrix4 proj_matrix;
469  proj_matrix = Ogre::Matrix4::ZERO;
470 
471  proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
472  proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
473 
474  proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
475  proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
476 
477  proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
478  proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
479 
480  proj_matrix[3][2]= -1;
481 
482  render_panel_->getCamera()->setCustomProjectionMatrix( true, proj_matrix );
483 
484  setStatus( StatusProperty::Ok, "Camera Info", "OK" );
485 
486 #if 0
487  static Axes* debug_axes = new Axes(scene_manager_, 0, 0.2, 0.01);
488  debug_axes->setPosition(position);
489  debug_axes->setOrientation(orientation);
490 #endif
491 
492  //adjust the image rectangles to fit the zoom & aspect ratio
493  double x_corner_start, y_corner_start, x_corner_end, y_corner_end;
494 
495  if ( info->roi.height != 0 || info->roi.width != 0 )
496  {
497  //corners are computed according to roi
498  x_corner_start = (2.0 * info->roi.x_offset / info->width - 1.0) * zoom_x;
499  y_corner_start = (-2.0 * info->roi.y_offset / info->height + 1.0) * zoom_y;
500  x_corner_end = x_corner_start + (2.0 * info->roi.width / info->width) * zoom_x;
501  y_corner_end = y_corner_start - (2.0 * info->roi.height / info->height) * zoom_y;
502  }
503  else
504  {
505  x_corner_start = -1.0f*zoom_x;
506  y_corner_start = 1.0f*zoom_y;
507  x_corner_end = 1.0f*zoom_x;
508  y_corner_end = -1.0f*zoom_y;
509  }
510 
511  bg_screen_rect_->setCorners( x_corner_start, y_corner_start, x_corner_end, y_corner_end);
512  fg_screen_rect_->setCorners( x_corner_start, y_corner_start, x_corner_end, y_corner_end);
513 
514  Ogre::AxisAlignedBox aabInf;
515  aabInf.setInfinite();
516  bg_screen_rect_->setBoundingBox( aabInf );
517  fg_screen_rect_->setBoundingBox( aabInf );
518 
519  setStatus( StatusProperty::Ok, "Time", "ok" );
520  setStatus( StatusProperty::Ok, "Camera Info", "ok" );
521 
522  return true;
523 }
524 
525 void CameraDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
526 {
527  texture_.addMessage(msg);
528 }
529 
530 void CameraDisplay::caminfoCallback( const sensor_msgs::CameraInfo::ConstPtr& msg )
531 {
532  boost::mutex::scoped_lock lock( caminfo_mutex_ );
533  current_caminfo_ = msg;
534  new_caminfo_ = true;
535 }
536 
538 {
539  std::string targetFrame = fixed_frame_.toStdString();
540  caminfo_tf_filter_->setTargetFrame(targetFrame);
542 }
543 
545 {
547  clear();
548 }
549 
550 } // namespace rviz
551 
std::string getTopic() const
void setMin(float min)
FloatProperty * alpha_property_
const Ogre::TexturePtr & getTexture()
void subscribe()
ROS topic management.
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
void setMax(float max)
Ogre::SceneNode * bg_scene_node_
void connectInput(F &f)
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
static const QString OVERLAY
static const QString BOTH
f
virtual tf::TransformListener * getTFClient() const =0
Convenience function: returns getFrameManager()->getTFClient().
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:256
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
Implement this to process the contents of a message.
std::string target_frame
void setAutoRender(bool auto_render)
virtual void onInitialize()
Override this function to do subclass-specific initialization.
virtual int getInt() const
Return the internal property value as an integer.
Definition: int_property.h:73
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
XmlRpcServer s
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:269
RenderPanel * render_panel_
virtual float getFloat() const
tf::MessageFilter< sensor_msgs::CameraInfo > * caminfo_tf_filter_
Ogre::SceneNode * fg_scene_node_
virtual void updateQueueSize()
Property specialized to enforce floating point max/min.
ros::Time getTime()
Get current time, depending on the sync mode.
boost::mutex caminfo_mutex_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:264
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
virtual DisplayGroup * getRootDisplayGroup() const =0
virtual void setPosition(const Ogre::Vector3 &position)
Set the position of this object.
Definition: axes.cpp:84
bool isEnabled() const
Return true if this Display is enabled, false if not.
Definition: display.cpp:281
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:281
virtual void setQueueSize(uint32_t new_queue_size)
virtual void setIcon(const QIcon &icon)
Set the icon to be displayed next to the property.
Definition: property.h:187
IntProperty * queue_size_property_
Ogre::RenderWindow * getRenderWindow()
Definition: render_widget.h:50
std::stringstream subclass which defaults to the "C" locale, so serialization of numbers is uniform a...
EnumProperty * image_position_property_
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves.
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
virtual void subscribe()
ROS topic management.
Display subclass for subscribing and displaying to image messages.
void enableTFFilter(std::string &targetFrame)
Enabling TF filtering by defining a target frame.
void addMessage(const sensor_msgs::Image::ConstPtr &image)
virtual BitAllocator * visibilityBits()=0
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves.
void setAssociatedWidget(QWidget *widget)
Associate the given widget with this Display.
Definition: display.cpp:357
Ogre::Rectangle2D * fg_screen_rect_
virtual void updateQueueSize()
Update queue size of tf filter.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
DisplayGroupVisibilityProperty * visibility_property_
virtual void reset()
Reset display.
std::string getCameraInfoTopic(const std::string &base_topic)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:58
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:261
virtual void onInitialize()
Override this function to do subclass-specific initialization.
FloatProperty * zoom_property_
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
virtual void reset()
Reset display.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
Ogre::Viewport * getViewport() const
RosTopicProperty * topic_property_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Ogre::Camera * getCamera() const
SyncMode getSyncMode()
virtual void addChild(Property *child, int index=-1)
Add a child property.
Definition: property.cpp:350
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
Ogre::MaterialPtr fg_material_
virtual void setOrientation(const Ogre::Quaternion &orientation)
Set the orientation of the object.
Definition: axes.cpp:89
static const QString BACKGROUND
void setTargetFrame(const std::string &target_frame)
Ogre::Rectangle2D * bg_screen_rect_
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:247
const sensor_msgs::Image::ConstPtr & getImage()
std::string getTopicStd() const
virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager.
Ogre::MaterialPtr bg_material_
void freeBits(uint32_t bits)
Free the given bits.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ROSImageTexture texture_
Enum property.
Definition: enum_property.h:47
QPixmap loadPixmap(QString url, bool fill_cache)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:186
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:159
void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
void setOverlaysEnabled(bool overlays_enabled)
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)
uint32_t allocBit()
Return a uint32 with a single bit "on" (previously unused), or a 0 if all bits are already allocated...


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat Apr 27 2019 02:33:41