overlay_camera_display.cpp
Go to the documentation of this file.
1 // -*- mode: c++; -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <boost/bind.hpp>
37 
38 #include <OgreManualObject.h>
39 #include <OgreMaterialManager.h>
40 #include <OgreRectangle2D.h>
41 #include <OgreRenderSystem.h>
42 #include <OgreRenderWindow.h>
43 #include <OgreSceneManager.h>
44 #include <OgreSceneNode.h>
45 #include <OgreTextureManager.h>
46 #include <OgreViewport.h>
47 #include <OgreTechnique.h>
48 #include <OgreCamera.h>
49 #include <OgrePixelFormat.h>
50 #include <OGRE/OgreHardwarePixelBuffer.h>
51 #include <OGRE/OgreTechnique.h>
52 #include <tf/transform_listener.h>
53 
54 #include "rviz/bit_allocator.h"
55 #include "rviz/frame_manager.h"
56 #include "rviz/ogre_helpers/axes.h"
61 #include "rviz/render_panel.h"
63 #include "rviz/validate_floats.h"
64 #include "rviz/display_context.h"
66 #include "rviz/load_resource.h"
67 
69 #include "overlay_camera_display.h"
70 
71 namespace jsk_rviz_plugins
72 {
73 using namespace rviz;
74 const QString OverlayCameraDisplay::BACKGROUND( "background" );
75 const QString OverlayCameraDisplay::OVERLAY( "overlay" );
76 const QString OverlayCameraDisplay::BOTH( "background and overlay" );
77 
78 bool validateFloats(const sensor_msgs::CameraInfo& msg)
79 {
80  bool valid = true;
81  valid = valid && rviz::validateFloats( msg.D );
82  valid = valid && rviz::validateFloats( msg.K );
83  valid = valid && rviz::validateFloats( msg.R );
84  valid = valid && rviz::validateFloats( msg.P );
85  return valid;
86 }
87 
90  , texture_()
91  , render_panel_( 0 )
92  , caminfo_tf_filter_( 0 )
93  , new_caminfo_( false )
94  , force_render_( false )
95  , caminfo_ok_(false)
96 {
97  image_position_property_ = new EnumProperty( "Image Rendering", BOTH,
98  "Render the image behind all other geometry or overlay it on top, or both.",
99  this, SLOT( forceRender() ));
103 
104  alpha_property_ = new FloatProperty( "Overlay Alpha", 0.5,
105  "The amount of transparency to apply to the camera image when rendered as overlay.",
106  this, SLOT( updateAlpha() ));
107  alpha_property_->setMin( 0 );
108  alpha_property_->setMax( 1 );
109 
110 
111  zoom_property_ = new FloatProperty( "Zoom Factor", 1.0,
112  "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
113  this, SLOT( forceRender() ));
114  zoom_property_->setMin( 0.00001 );
115  zoom_property_->setMax( 100000 );
116 
117  width_property_ = new IntProperty("width", 640,
118  "width of overlay image",
119  this, SLOT(updateWidth()));
120  height_property_ = new IntProperty("height", 480,
121  "height of overlay image",
122  this, SLOT(updateHeight()));
123  left_property_ = new IntProperty("left", 0,
124  "left positoin of overlay image",
125  this, SLOT(updateLeft()));
126  top_property_ = new IntProperty("top", 0,
127  "top positoin of overlay image",
128  this, SLOT(updateTop()));
129  texture_alpha_property_ = new FloatProperty("texture alpha", 0.8,
130  "texture alpha",
131  this, SLOT(updateTextureAlpha()));
134 }
135 
137 {
138  if ( initializedp_ )
139  {
140  render_panel_->getRenderWindow()->removeListener( this );
141 
142  unsubscribe();
144 
145 
146  //workaround. delete results in a later crash
147  render_panel_->hide();
148  //delete render_panel_;
149 
150  delete bg_screen_rect_;
151  delete fg_screen_rect_;
152 
153  bg_scene_node_->getParentSceneNode()->removeAndDestroyChild( bg_scene_node_->getName() );
154  fg_scene_node_->getParentSceneNode()->removeAndDestroyChild( fg_scene_node_->getName() );
155 
156  delete caminfo_tf_filter_;
157 
159  }
160 }
161 
163 {
165 
166 #if ROS_VERSION_MINIMUM(1, 15, 0) // noetic and greater
168  *context_->getTF2BufferPtr(), fixed_frame_.toStdString(),
170 #else
172  *context_->getTFClient(), fixed_frame_.toStdString(),
174 #endif
175 
176  bg_scene_node_ = scene_node_->createChildSceneNode();
177  fg_scene_node_ = scene_node_->createChildSceneNode();
178 
179  {
180  static int count = 0;
182  ss << "OverlayCameraDisplayObject" << count++;
183 
184  //background rectangle
185  bg_screen_rect_ = new Ogre::Rectangle2D(true);
186  bg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
187 
188  ss << "Material";
189  bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
190  bg_material_->setDepthWriteEnabled(false);
191 
192  bg_material_->setReceiveShadows(false);
193  bg_material_->setDepthCheckEnabled(false);
194 
195  bg_material_->getTechnique(0)->setLightingEnabled(false);
196  Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
197  tu->setTextureName(texture_.getTexture()->getName());
198  tu->setTextureFiltering( Ogre::TFO_NONE );
199  tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
200 
201  bg_material_->setCullingMode(Ogre::CULL_NONE);
202  bg_material_->setSceneBlending( Ogre::SBT_REPLACE );
203 
204  Ogre::AxisAlignedBox aabInf;
205  aabInf.setInfinite();
206 
207  bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
208  bg_screen_rect_->setBoundingBox(aabInf);
209  bg_screen_rect_->setMaterial(bg_material_->getName());
210 
211  bg_scene_node_->attachObject(bg_screen_rect_);
212  bg_scene_node_->setVisible(false);
213 
214  //overlay rectangle
215  fg_screen_rect_ = new Ogre::Rectangle2D(true);
216  fg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
217 
218  fg_material_ = bg_material_->clone( ss.str()+"fg" );
219  fg_screen_rect_->setBoundingBox(aabInf);
220  fg_screen_rect_->setMaterial(fg_material_->getName());
221 
222  fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
223  fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
224 
225  fg_scene_node_->attachObject(fg_screen_rect_);
226  fg_scene_node_->setVisible(false);
227  }
228 
229  updateAlpha();
230 
231  updateWidth();
232  updateHeight();
233  updateLeft();
234  updateTop();
236 
237  render_panel_ = new RenderPanel();
238  render_panel_->getRenderWindow()->addListener( this );
239  render_panel_->getRenderWindow()->setAutoUpdated(false);
240  render_panel_->getRenderWindow()->setActive( false );
241  render_panel_->resize( 640, 480 );
243 
244  //setAssociatedWidget( render_panel_ );
245 
248  render_panel_->getCamera()->setNearClipDistance( 0.01f );
249 
250  caminfo_tf_filter_->connectInput(caminfo_sub_);
251  caminfo_tf_filter_->registerCallback(boost::bind(&OverlayCameraDisplay::caminfoCallback, this, _1));
252  //context_->getFrameManager()->registerFilterForTransformStatusCheck(caminfo_tf_filter_, this);
253 
255  render_panel_->getViewport()->setVisibilityMask( vis_bit_ );
256 
258  vis_bit_, context_->getRootDisplayGroup(), this, "Visibility", true,
259  "Changes the visibility of other Displays in the camera view.");
260 
261  visibility_property_->setIcon( loadPixmap("package://rviz/icons/visibility.svg",true) );
262 
263  this->addChild( visibility_property_, 0 );
264  initializedp_ = true;
265 }
266 
267 void OverlayCameraDisplay::preRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
268 {
269  QString image_position = image_position_property_->getString();
270  bg_scene_node_->setVisible( caminfo_ok_ && (image_position == BACKGROUND || image_position == BOTH) );
271  fg_scene_node_->setVisible( caminfo_ok_ && (image_position == OVERLAY || image_position == BOTH) );
272 
273  // set view flags on all displays
275 }
276 
277 void OverlayCameraDisplay::postRenderTargetUpdate(const Ogre::RenderTargetEvent& evt)
278 {
279  bg_scene_node_->setVisible( false );
280  fg_scene_node_->setVisible( false );
281 }
282 
284 {
285  subscribe();
286  render_panel_->getRenderWindow()->setActive(true);
287  if (overlay_) {
288  overlay_->show();
289  }
290 }
291 
293 {
294  render_panel_->getRenderWindow()->setActive(false);
295  unsubscribe();
296  clear();
297  if (overlay_) {
298  overlay_->hide();
299  }
300 }
301 
303 {
304  if ( (!isEnabled()) || (topic_property_->getTopicStd().empty()) )
305  {
306  return;
307  }
308 
309  std::string target_frame = fixed_frame_.toStdString();
310  ImageDisplayBase::enableTFFilter(target_frame);
311 
313 
314  std::string topic = topic_property_->getTopicStd();
315  std::string caminfo_topic = image_transport::getCameraInfoTopic(topic_property_->getTopicStd());
316 
317  try
318  {
319  caminfo_sub_.subscribe( update_nh_, caminfo_topic, 1 );
320  setStatus( StatusProperty::Ok, "Camera Info", "OK" );
321  }
322  catch( ros::Exception& e )
323  {
324  setStatus( StatusProperty::Error, "Camera Info", QString( "Error subscribing: ") + e.what() );
325  }
326 }
327 
329 {
332 }
333 
335 {
336  float alpha = alpha_property_->getFloat();
337 
338  Ogre::Pass* pass = fg_material_->getTechnique( 0 )->getPass( 0 );
339  if( pass->getNumTextureUnitStates() > 0 )
340  {
341  Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState( 0 );
342  tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
343  }
344  else
345  {
346  fg_material_->setAmbient( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
347  fg_material_->setDiffuse( Ogre::ColourValue( 0.0f, 1.0f, 1.0f, alpha ));
348  }
349 
350  force_render_ = true;
352 }
353 
355 {
356  force_render_ = true;
358 }
359 
361 {
364 }
365 
367 {
368  texture_.clear();
369  force_render_ = true;
371 
372  new_caminfo_ = false;
373  current_caminfo_.reset();
374 
375  setStatus( StatusProperty::Warn, "Camera Info",
376  "No CameraInfo received on [" + QString::fromStdString( caminfo_sub_.getTopic() ) + "]. Topic may not exist.");
377  setStatus( StatusProperty::Warn, "Image", "No Image received");
378 
379  render_panel_->getCamera()->setPosition( Ogre::Vector3( 999999, 999999, 999999 ));
380 }
381 
382 void OverlayCameraDisplay::update( float wall_dt, float ros_dt )
383 {
384  try
385  {
386  if( texture_.update() || force_render_ )
387  {
389  force_render_ = false;
390  }
391  }
392  catch( UnsupportedImageEncoding& e )
393  {
394  setStatus( StatusProperty::Error, "Image", e.what() );
395  }
396 
397  render_panel_->getRenderWindow()->update();
398  if (!overlay_) {
399  static int count = 0;
401  ss << "OverlayCameraImageDisplayObject" << count++;
402  overlay_.reset(new OverlayObject(ss.str()));
403  overlay_->show();
404  }
405  overlay_->updateTextureSize(render_panel_->getRenderWindow()->getWidth(),
406  render_panel_->getRenderWindow()->getHeight());
407  redraw();
408  overlay_->setDimensions(width_, height_);
409  overlay_->setPosition(left_, top_);
410 }
411 
413 {
414  Ogre::RenderTarget *rt = render_panel_->getRenderWindow();
415  int width = rt->getWidth();
416  int height = rt->getHeight();
417  Ogre::uchar *data = new Ogre::uchar[width * height * 3];
418  Ogre::PixelBox pb(width, height, 1, Ogre::PF_BYTE_RGB, data);
419  rt->copyContentsToMemory(pb);
420  {
421  ScopedPixelBuffer buffer = overlay_->getBuffer();
422  QImage Hud = buffer.getQImage(*overlay_);
423  for (int i = 0; i < overlay_->getTextureWidth(); i++) {
424  for (int j = 0; j < overlay_->getTextureHeight(); j++) {
425  Ogre::ColourValue c = pb.getColourAt(i, j, 0);
426  QColor color(c.r * 255, c.g * 255, c.b * 255, texture_alpha_ * 255);
427  Hud.setPixel(i, j, color.rgba());
428  }
429  }
430  }
431  delete[] data;
432 }
433 
435 {
436  sensor_msgs::CameraInfo::ConstPtr info;
437  sensor_msgs::Image::ConstPtr image;
438  {
439  boost::mutex::scoped_lock lock( caminfo_mutex_ );
440 
441  info = current_caminfo_;
442  image = texture_.getImage();
443  }
444 
445  if( !info || !image )
446  {
447  return false;
448  }
449 
450  if( !validateFloats( *info ))
451  {
452  setStatus( StatusProperty::Error, "Camera Info", "Contains invalid floating point values (nans or infs)" );
453  return false;
454  }
455 
456  // if we're in 'exact' time mode, only show image if the time is exactly right
457  ros::Time rviz_time = context_->getFrameManager()->getTime();
459  rviz_time != image->header.stamp )
460  {
461  std::ostringstream s;
462  s << "Time-syncing active and no image at timestamp " << rviz_time.toSec() << ".";
463  setStatus( StatusProperty::Warn, "Time", s.str().c_str() );
464  return false;
465  }
466 
467  Ogre::Vector3 position;
468  Ogre::Quaternion orientation;
469  context_->getFrameManager()->getTransform( image->header.frame_id, image->header.stamp, position, orientation );
470 
471  //printf( "OverlayCameraDisplay:updateCamera(): pos = %.2f, %.2f, %.2f.\n", position.x, position.y, position.z );
472 
473  // convert vision (Z-forward) frame to ogre frame (Z-out)
474  orientation = orientation * Ogre::Quaternion( Ogre::Degree( 180 ), Ogre::Vector3::UNIT_X );
475 
476  float img_width = info->width;
477  float img_height = info->height;
478 
479  // If the image width is 0 due to a malformed caminfo, try to grab the width from the image.
480  if( img_width == 0 )
481  {
482  ROS_DEBUG( "Malformed CameraInfo on camera [%s], width = 0", qPrintable( getName() ));
483  img_width = texture_.getWidth();
484  }
485 
486  if (img_height == 0)
487  {
488  ROS_DEBUG( "Malformed CameraInfo on camera [%s], height = 0", qPrintable( getName() ));
489  img_height = texture_.getHeight();
490  }
491 
492  if( img_height == 0.0 || img_width == 0.0 )
493  {
494  setStatus( StatusProperty::Error, "Camera Info",
495  "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)" );
496  return false;
497  }
498 
499  double fx = info->P[0];
500  double fy = info->P[5];
501 
502  float win_width = render_panel_->width();
503  float win_height = render_panel_->height();
504  float zoom_x = zoom_property_->getFloat();
505  float zoom_y = zoom_x;
506 
507  // Preserve aspect ratio
508  if( win_width != 0 && win_height != 0 )
509  {
510  float img_aspect = (img_width/fx) / (img_height/fy);
511  float win_aspect = win_width / win_height;
512 
513  if ( img_aspect > win_aspect )
514  {
515  zoom_y = zoom_y / img_aspect * win_aspect;
516  }
517  else
518  {
519  zoom_x = zoom_x / win_aspect * img_aspect;
520  }
521  }
522 
523  // Add the camera's translation relative to the left camera (from P[3]);
524  double tx = -1 * (info->P[3] / fx);
525  Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
526  position = position + (right * tx);
527 
528  double ty = -1 * (info->P[7] / fy);
529  Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
530  position = position + (down * ty);
531 
532  if( !rviz::validateFloats( position ))
533  {
534  setStatus( StatusProperty::Error, "Camera Info", "CameraInfo/P resulted in an invalid position calculation (nans or infs)" );
535  return false;
536  }
537 
538  render_panel_->getCamera()->setPosition( position );
539  render_panel_->getCamera()->setOrientation( orientation );
540 
541  // calculate the projection matrix
542  double cx = info->P[2];
543  double cy = info->P[6];
544 
545  double far_plane = 100;
546  double near_plane = 0.01;
547 
548  Ogre::Matrix4 proj_matrix;
549  proj_matrix = Ogre::Matrix4::ZERO;
550 
551  proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
552  proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
553 
554  proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
555  proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
556 
557  proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
558  proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
559 
560  proj_matrix[3][2]= -1;
561 
562  render_panel_->getCamera()->setCustomProjectionMatrix( true, proj_matrix );
563  render_panel_->resize(info->width, info->height);
564  setStatus( StatusProperty::Ok, "Camera Info", "OK" );
565 
566 #if 0
567  static Axes* debug_axes = new Axes(scene_manager_, 0, 0.2, 0.01);
568  debug_axes->setPosition(position);
569  debug_axes->setOrientation(orientation);
570 #endif
571 
572  //adjust the image rectangles to fit the zoom & aspect ratio
573  bg_screen_rect_->setCorners( -1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y );
574  fg_screen_rect_->setCorners( -1.0f*zoom_x, 1.0f*zoom_y, 1.0f*zoom_x, -1.0f*zoom_y );
575 
576  Ogre::AxisAlignedBox aabInf;
577  aabInf.setInfinite();
578  bg_screen_rect_->setBoundingBox( aabInf );
579  fg_screen_rect_->setBoundingBox( aabInf );
580 
581  setStatus( StatusProperty::Ok, "Time", "ok" );
582  setStatus( StatusProperty::Ok, "Camera Info", "ok" );
583 
584  return true;
585 }
586 
587 void OverlayCameraDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
588 {
589  texture_.addMessage(msg);
590 }
591 
592 void OverlayCameraDisplay::caminfoCallback( const sensor_msgs::CameraInfo::ConstPtr& msg )
593 {
594  boost::mutex::scoped_lock lock( caminfo_mutex_ );
595  current_caminfo_ = msg;
596  new_caminfo_ = true;
597 }
598 
600 {
601  std::string targetFrame = fixed_frame_.toStdString();
602  caminfo_tf_filter_->setTargetFrame(targetFrame);
604 }
605 
607 {
609  clear();
610 }
611 
613 {
615 }
616 
618 {
620 }
621 
623 {
625 }
626 
628 {
630 }
631 
633 {
635 }
636 
637 }
638 
f
void setMin(float min)
const Ogre::TexturePtr & getTexture()
void setOrientation(const Ogre::Quaternion &orientation) override
void setMax(float max)
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
virtual tf::TransformListener * getTFClient() const=0
virtual QImage getQImage(unsigned int width, unsigned int height)
std::string getTopic() const
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
std::string target_frame
void setAutoRender(bool auto_render)
Ogre::Camera * getCamera() const
ros::NodeHandle update_nh_
data
virtual void unsubscribe()
width
DisplayGroupVisibilityProperty * visibility_property_
ros::Time getTime()
std::string getTopicStd() const
void reset() override
Ogre::SceneNode * scene_node_
virtual DisplayGroup * getRootDisplayGroup() const=0
QString fixed_frame_
virtual void setQueueSize(uint32_t new_queue_size)
virtual void setIcon(const QIcon &icon)
virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
IntProperty * queue_size_property_
Ogre::RenderWindow * getRenderWindow()
virtual void addOption(const QString &option, int value=0)
virtual void subscribe()
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
void enableTFFilter(std::string &targetFrame)
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
void addMessage(const sensor_msgs::Image::ConstPtr &image)
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
virtual BitAllocator * visibilityBits()=0
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual QString getName() const
topic
virtual void updateQueueSize()
Ogre::Viewport * getViewport() const
void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
virtual FrameManager * getFrameManager() const=0
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
void fixedFrameChanged() override
void onInitialize() override
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
Ogre::SceneManager * scene_manager_
void setPosition(const Ogre::Vector3 &position) override
virtual int getInt() const
virtual Ogre::SceneManager * getSceneManager() const=0
virtual std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const=0
virtual void queueRender()=0
bool isEnabled() 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)
virtual float getFloat() const
SyncMode getSyncMode()
virtual void addChild(Property *child, int index=-1)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
void setTargetFrame(const std::string &target_frame)
boost::arg< 1 > _1
tf::MessageFilter< sensor_msgs::CameraInfo > * caminfo_tf_filter_
height
const sensor_msgs::Image::ConstPtr & getImage()
void freeBits(uint32_t bits)
QPixmap loadPixmap(QString url, bool fill_cache)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
void setOverlaysEnabled(bool overlays_enabled)
virtual void update(float wall_dt, float ros_dt)
Connection registerCallback(const C &callback)
#define ROS_DEBUG(...)
uint32_t allocBit()


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Thu Jun 1 2023 02:45:58