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 <tf2_ros/message_filter.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 const QString CameraDisplay::BACKGROUND("background");
67 const QString CameraDisplay::OVERLAY("overlay");
68 const QString CameraDisplay::BOTH("background and overlay");
69 
70 bool validateFloats(const sensor_msgs::CameraInfo& msg)
71 {
72  bool valid = true;
73  valid = valid && validateFloats(msg.D);
74  valid = valid && validateFloats(msg.K);
75  valid = valid && validateFloats(msg.R);
76  valid = valid && validateFloats(msg.P);
77  return valid;
78 }
79 
81  : ImageDisplayBase(), texture_(), render_panel_(nullptr), caminfo_ok_(false), force_render_(false)
82 {
84  new EnumProperty("Image Rendering", BOTH,
85  "Render the image behind all other geometry or overlay it on top, or both.", this,
86  SLOT(forceRender()));
90 
92  "Overlay Alpha", 0.5,
93  "The amount of transparency to apply to the camera image when rendered as overlay.", this,
94  SLOT(updateAlpha()));
97 
99  "Zoom Factor", 1.0,
100  "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.", this,
101  SLOT(forceRender()));
102  zoom_property_->setMin(0.00001);
103  zoom_property_->setMax(100000);
104 }
105 
107 {
108  if (initialized())
109  {
110  render_panel_->getRenderWindow()->removeListener(this);
111 
112  unsubscribe();
113 
114  delete render_panel_;
115  delete bg_screen_rect_;
116  delete fg_screen_rect_;
117 
118  bg_scene_node_->getParentSceneNode()->removeAndDestroyChild(bg_scene_node_->getName());
119  fg_scene_node_->getParentSceneNode()->removeAndDestroyChild(fg_scene_node_->getName());
120 
122  }
123 }
124 
126 {
128 
129  bg_scene_node_ = scene_node_->createChildSceneNode();
130  fg_scene_node_ = scene_node_->createChildSceneNode();
131 
132  {
133  static int count = 0;
135  ss << "CameraDisplayObject" << count++;
136 
137  // background rectangle
138  bg_screen_rect_ = new Ogre::Rectangle2D(true);
139  bg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
140 
141  ss << "Material";
142  bg_material_ = Ogre::MaterialManager::getSingleton().create(
143  ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
144  bg_material_->setDepthWriteEnabled(false);
145 
146  bg_material_->setReceiveShadows(false);
147  bg_material_->setDepthCheckEnabled(false);
148 
149  bg_material_->getTechnique(0)->setLightingEnabled(false);
150  Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
151  tu->setTextureName(texture_.getTexture()->getName());
152  tu->setTextureFiltering(Ogre::TFO_NONE);
153  tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP);
154  tu->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0);
155 
156  bg_material_->setCullingMode(Ogre::CULL_NONE);
157  bg_material_->setSceneBlending(Ogre::SBT_REPLACE);
158 
159  Ogre::AxisAlignedBox aabInf;
160  aabInf.setInfinite();
161 
162  bg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_BACKGROUND);
163  bg_screen_rect_->setBoundingBox(aabInf);
164  bg_screen_rect_->setMaterial(bg_material_->getName());
165 
166  bg_scene_node_->attachObject(bg_screen_rect_);
167  bg_scene_node_->setVisible(false);
168 
169  // overlay rectangle
170  fg_screen_rect_ = new Ogre::Rectangle2D(true);
171  fg_screen_rect_->setCorners(-1.0f, 1.0f, 1.0f, -1.0f);
172 
173  fg_material_ = bg_material_->clone(ss.str() + "fg");
174  fg_screen_rect_->setBoundingBox(aabInf);
175  fg_screen_rect_->setMaterial(fg_material_->getName());
176 
177  fg_material_->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
178  fg_screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
179 
180  fg_scene_node_->attachObject(fg_screen_rect_);
181  fg_scene_node_->setVisible(false);
182  }
183 
184  updateAlpha();
185 
186  render_panel_ = new RenderPanel();
187  render_panel_->getRenderWindow()->addListener(this);
188  render_panel_->getRenderWindow()->setAutoUpdated(false);
189  render_panel_->getRenderWindow()->setActive(false);
190  render_panel_->resize(640, 480);
192 
194 
197  render_panel_->getCamera()->setNearClipDistance(0.01f);
198 
200 
202  render_panel_->getViewport()->setVisibilityMask(vis_bit_);
203 
206  true,
207  "Changes the visibility of other Displays in the camera view.");
208 
209  visibility_property_->setIcon(loadPixmap("package://rviz/icons/visibility.svg", true));
210 
211  this->addChild(visibility_property_, 0);
212 }
213 
214 void CameraDisplay::preRenderTargetUpdate(const Ogre::RenderTargetEvent& /*evt*/)
215 {
216  QString image_position = image_position_property_->getString();
217  bg_scene_node_->setVisible(caminfo_ok_ && (image_position == BACKGROUND || image_position == BOTH));
218  fg_scene_node_->setVisible(caminfo_ok_ && (image_position == OVERLAY || image_position == BOTH));
219 
220  // set view flags on all displays
222 }
223 
224 void CameraDisplay::postRenderTargetUpdate(const Ogre::RenderTargetEvent& /*evt*/)
225 {
226  bg_scene_node_->setVisible(false);
227  fg_scene_node_->setVisible(false);
228 }
229 
231 {
232  subscribe();
233  render_panel_->getRenderWindow()->setActive(true);
234 }
235 
237 {
238  render_panel_->getRenderWindow()->setActive(false);
239  unsubscribe();
240  reset();
241 }
242 
244 {
245  if ((!isEnabled()) || (topic_property_->getTopicStd().empty()))
246  {
247  return;
248  }
249 
250  std::string target_frame = fixed_frame_.toStdString();
251  ImageDisplayBase::enableTFFilter(target_frame);
253 
254  try
255  {
256  const std::string caminfo_topic =
258  caminfo_sub_.subscribe(update_nh_, caminfo_topic, 1);
259  }
260  catch (ros::Exception& e)
261  {
262  setStatus(StatusProperty::Error, "Camera Info", QString("Error subscribing: ") + e.what());
263  }
264 }
265 
267 {
270 
271  boost::mutex::scoped_lock lock(caminfo_mutex_);
272  current_caminfo_.reset();
273 }
274 
276 {
277  float alpha = alpha_property_->getFloat();
278 
279  Ogre::Pass* pass = fg_material_->getTechnique(0)->getPass(0);
280  if (pass->getNumTextureUnitStates() > 0)
281  {
282  Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState(0);
283  tex_unit->setAlphaOperation(Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha);
284  }
285  else
286  {
287  fg_material_->setAmbient(Ogre::ColourValue(0.0f, 1.0f, 1.0f, alpha));
288  fg_material_->setDiffuse(Ogre::ColourValue(0.0f, 1.0f, 1.0f, alpha));
289  }
290 
291  force_render_ = true;
293 }
294 
296 {
297  force_render_ = true;
299 }
300 
302 {
304 }
305 
306 // TODO: In Noetic remove and integrate into reset()
308 {
309  texture_.clear();
310  force_render_ = true;
312  render_panel_->getCamera()->setPosition(Ogre::Vector3(999999, 999999, 999999));
313 }
314 
315 void CameraDisplay::update(float /*wall_dt*/, float /*ros_dt*/)
316 {
317  try
318  {
319  if (texture_.update() || force_render_)
320  {
322  force_render_ = false;
323  }
324  }
325  catch (UnsupportedImageEncoding& e)
326  {
327  setStatus(StatusProperty::Error, "Image", e.what());
328  }
329 
330  render_panel_->getRenderWindow()->update();
331 }
332 
334 {
335  sensor_msgs::CameraInfo::ConstPtr info;
336  sensor_msgs::Image::ConstPtr image;
337  {
338  boost::mutex::scoped_lock lock(caminfo_mutex_);
339 
340  info = current_caminfo_;
341  image = texture_.getImage();
342  }
343 
344  if (!info || !image)
345  {
346  return false;
347  }
348 
349  if (image->header.frame_id != info->header.frame_id)
350  setStatus(StatusProperty::Warn, "Image frame",
351  QString("Image frame (%1) doesn't match camera frame (%2)")
352  .arg(QString::fromStdString(image->header.frame_id),
353  QString::fromStdString(info->header.frame_id)));
354  else
355  deleteStatus("Image frame");
356 
357  if (!validateFloats(*info))
358  {
359  setStatus(StatusProperty::Error, "Camera Info",
360  "Contains invalid floating point values (nans or infs)");
361  return false;
362  }
363 
364  // if we're in 'exact' time mode, only show image if the time is exactly right
365  ros::Time rviz_time = context_->getFrameManager()->getTime();
367  rviz_time != image->header.stamp)
368  {
369  std::ostringstream s;
370  s << "Time-syncing active and no image at timestamp " << rviz_time.toSec() << ".";
371  setStatus(StatusProperty::Warn, "Time", s.str().c_str());
372  return false;
373  }
374 
375  Ogre::Vector3 position;
376  Ogre::Quaternion orientation;
377  context_->getFrameManager()->getTransform(image->header.frame_id, image->header.stamp, position,
378  orientation);
379 
380  // printf( "CameraDisplay:updateCamera(): pos = %.2f, %.2f, %.2f.\n", position.x, position.y,
381  // position.z );
382 
383  // convert vision (Z-forward) frame to ogre frame (Z-out)
384  orientation = orientation * Ogre::Quaternion(Ogre::Degree(180), Ogre::Vector3::UNIT_X);
385 
386  float img_width = info->width;
387  float img_height = info->height;
388 
389  // If the image width is 0 due to a malformed caminfo, try to grab the width from the image.
390  if (img_width == 0)
391  {
392  ROS_DEBUG("Malformed CameraInfo on camera [%s], width = 0", qPrintable(getName()));
393  img_width = texture_.getWidth();
394  }
395 
396  if (img_height == 0)
397  {
398  ROS_DEBUG("Malformed CameraInfo on camera [%s], height = 0", qPrintable(getName()));
399  img_height = texture_.getHeight();
400  }
401 
402  if (img_height == 0.0 || img_width == 0.0)
403  {
404  setStatus(StatusProperty::Error, "Camera Info",
405  "Could not determine width/height of image due to malformed CameraInfo "
406  "(either width or height is 0)");
407  return false;
408  }
409 
410  double fx = info->P[0];
411  double fy = info->P[5];
412 
413  float win_width = render_panel_->width();
414  float win_height = render_panel_->height();
415  float zoom_x = zoom_property_->getFloat();
416  float zoom_y = zoom_x;
417 
418  // Preserve aspect ratio
419  if (win_width != 0 && win_height != 0)
420  {
421  float img_aspect = (img_width / fx) / (img_height / fy);
422  float win_aspect = win_width / win_height;
423 
424  if (img_aspect > win_aspect)
425  {
426  zoom_y = zoom_y / img_aspect * win_aspect;
427  }
428  else
429  {
430  zoom_x = zoom_x / win_aspect * img_aspect;
431  }
432  }
433 
434  // Add the camera's translation relative to the left camera (from P[3]);
435  double tx = -1 * (info->P[3] / fx);
436  Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
437  position = position + (right * tx);
438 
439  double ty = -1 * (info->P[7] / fy);
440  Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
441  position = position + (down * ty);
442 
443  if (!validateFloats(position))
444  {
445  setStatus(StatusProperty::Error, "Camera Info",
446  "CameraInfo/P resulted in an invalid position calculation (nans or infs)");
447  return false;
448  }
449 
450  render_panel_->getCamera()->setPosition(position);
451  render_panel_->getCamera()->setOrientation(orientation);
452 
453  // calculate the projection matrix
454  double cx = info->P[2];
455  double cy = info->P[6];
456 
457  double far_plane = 100;
458  double near_plane = 0.01;
459 
460  Ogre::Matrix4 proj_matrix;
461  proj_matrix = Ogre::Matrix4::ZERO;
462 
463  proj_matrix[0][0] = 2.0 * fx / img_width * zoom_x;
464  proj_matrix[1][1] = 2.0 * fy / img_height * zoom_y;
465 
466  proj_matrix[0][2] = 2.0 * (0.5 - cx / img_width) * zoom_x;
467  proj_matrix[1][2] = 2.0 * (cy / img_height - 0.5) * zoom_y;
468 
469  proj_matrix[2][2] = -(far_plane + near_plane) / (far_plane - near_plane);
470  proj_matrix[2][3] = -2.0 * far_plane * near_plane / (far_plane - near_plane);
471 
472  proj_matrix[3][2] = -1;
473 
474  render_panel_->getCamera()->setCustomProjectionMatrix(true, proj_matrix);
475 
476 #if 0
477  static Axes* debug_axes = new Axes(scene_manager_, 0, 0.2, 0.01);
478  debug_axes->setPosition(position);
479  debug_axes->setOrientation(orientation);
480 #endif
481 
482  // adjust the image rectangles to fit the zoom & aspect ratio
483  double x_corner_start, y_corner_start, x_corner_end, y_corner_end;
484 
485  if (info->roi.height != 0 || info->roi.width != 0)
486  {
487  // corners are computed according to roi
488  x_corner_start = (2.0 * info->roi.x_offset / info->width - 1.0) * zoom_x;
489  y_corner_start = (-2.0 * info->roi.y_offset / info->height + 1.0) * zoom_y;
490  x_corner_end = x_corner_start + (2.0 * info->roi.width / info->width) * zoom_x;
491  y_corner_end = y_corner_start - (2.0 * info->roi.height / info->height) * zoom_y;
492  }
493  else
494  {
495  x_corner_start = -1.0f * zoom_x;
496  y_corner_start = 1.0f * zoom_y;
497  x_corner_end = 1.0f * zoom_x;
498  y_corner_end = -1.0f * zoom_y;
499  }
500 
501  bg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
502  fg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
503 
504  Ogre::AxisAlignedBox aabInf;
505  aabInf.setInfinite();
506  bg_screen_rect_->setBoundingBox(aabInf);
507  fg_screen_rect_->setBoundingBox(aabInf);
508 
509  setStatus(StatusProperty::Ok, "Time", "OK");
510  setStatus(StatusProperty::Ok, "Camera Info", "processed");
511 
512  return true;
513 }
514 
515 void CameraDisplay::processMessage(const sensor_msgs::Image::ConstPtr& msg)
516 {
517  texture_.addMessage(msg);
518 }
519 
520 void CameraDisplay::caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg)
521 {
522  boost::mutex::scoped_lock lock(caminfo_mutex_);
523  current_caminfo_ = msg;
524  setStatus(StatusProperty::Ok, "Camera Info", "received");
525 }
526 
528 {
530 }
531 
533 {
534  clear();
536  // We explicitly do not reset current_caminfo_ here: If we are subscribed to a latched caminfo topic,
537  // we will not receive another message after reset, i.e. the caminfo could not be recovered.
538  // Thus, we reset caminfo only if unsubscribing.
539 
540  const std::string topic = topic_property_->getTopicStd();
541  if (!topic.empty())
542  {
543  const std::string caminfo_topic = image_transport::getCameraInfoTopic(topic);
544  boost::mutex::scoped_lock lock(caminfo_mutex_);
545  if (!current_caminfo_)
546  setStatus(StatusProperty::Warn, "Camera Info",
547  "No CameraInfo received on [" + QString::fromStdString(caminfo_topic) +
548  "].\nTopic may not exist.");
549  }
550 }
551 
552 } // namespace rviz
553 
void setMin(float min)
FloatProperty * alpha_property_
const Ogre::TexturePtr & getTexture()
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Definition: axes.cpp:88
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void setMax(float max)
Ogre::SceneNode * bg_scene_node_
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
static const QString OVERLAY
static const QString BOTH
f
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:287
std::string target_frame
void setAutoRender(bool auto_render)
XmlRpcServer s
Ogre::Camera * getCamera() const
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:300
RenderPanel * render_panel_
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
Ogre::SceneNode * fg_scene_node_
void subscribe() override
ROS topic management.
Property specialized to enforce floating point max/min.
ros::Time getTime()
Get current time, depending on the sync mode.
std::string getTopicStd() const
boost::mutex caminfo_mutex_
void reset() override
Reset display.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
virtual DisplayGroup * getRootDisplayGroup() const =0
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
virtual void setIcon(const QIcon &icon)
Set the icon to be displayed next to the property.
Definition: property.h:193
Ogre::RenderWindow * getRenderWindow()
Definition: render_widget.h:49
std::stringstream subclass which defaults to the "C" locale, so serialization of numbers is uniform a...
EnumProperty * image_position_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
virtual void subscribe()
ROS topic management.
void unsubscribe() override
Display subclass for subscribing and displaying to image messages.
void enableTFFilter(std::string &targetFrame)
Enabling TF filtering by defining a target frame.
void onInitialize() override
Override this function to do subclass-specific initialization.
void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
void reset() override
Called to tell the display to clear its state.
void addMessage(const sensor_msgs::Image::ConstPtr &image)
virtual BitAllocator * visibilityBits()=0
void setAssociatedWidget(QWidget *widget)
Associate the given widget with this Display.
Definition: display.cpp:361
Ogre::Rectangle2D * fg_screen_rect_
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
virtual void updateQueueSize()
Update queue size of tf filter.
Ogre::Viewport * getViewport() const
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
DisplayGroupVisibilityProperty * visibility_property_
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void onInitialize() override
Override this function to do subclass-specific initialization.
IMAGE_TRANSPORT_DECL 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:59
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Definition: axes.cpp:83
FloatProperty * zoom_property_
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
bool isEnabled() const
Return true if this Display is enabled, false if not.
Definition: display.cpp:268
RosTopicProperty * topic_property_
void updateQueueSize() override
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)
Add a child property.
Definition: property.cpp:355
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.
Ogre::MaterialPtr fg_material_
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
static const QString BACKGROUND
virtual void deleteStatus(const QString &name)
Delete the status entry with the given name. This is thread-safe.
Definition: display.cpp:197
Ogre::Rectangle2D * bg_screen_rect_
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
const sensor_msgs::Image::ConstPtr & getImage()
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
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:46
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:175
void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
void processMessage(const sensor_msgs::Image::ConstPtr &msg) override
Implement this to process the contents of a message.
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 May 27 2023 02:06:24