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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:52