camera_info_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 
38 #include "camera_info_display.h"
39 #include <OGRE/OgreMaterialManager.h>
40 #include <OGRE/OgreMaterial.h>
41 #include <OGRE/OgreBlendMode.h>
42 #include <QImage>
43 #include <OGRE/OgreHardwarePixelBuffer.h>
45 
47 
48 namespace jsk_rviz_plugins
49 {
51  Ogre::SceneManager* manager,
52  Ogre::SceneNode* node,
53  const cv::Point3d& O,
54  const cv::Point3d& A,
55  const cv::Point3d& B,
56  const std::string& name,
57  const Ogre::ColourValue& color,
58  bool use_color,
59  bool upper_triangle)
60  {
61  // uniq string is requred for name
62 
63  manual_ = manager->createManualObject();
64  manual_->clear();
65  manual_->begin(name,
66  Ogre::RenderOperation::OT_TRIANGLE_STRIP);
67  manual_->position(O.x, O.y, O.z);
68  if (upper_triangle) {
69  manual_->textureCoord(0, 0);
70  }
71  else {
72  manual_->textureCoord(1, 0);
73  }
74  if (use_color) {
75  manual_->colour(color);
76  }
77  manual_->position(A.x, A.y, A.z);
78  if (upper_triangle) {
79  manual_->textureCoord(1, 0);
80  }
81  else {
82  manual_->textureCoord(1, 1);
83  }
84  if (use_color) {
85  manual_->colour(color);
86  }
87  manual_->position(B.x, B.y, B.z);
88  if (upper_triangle) {
89  manual_->textureCoord(0, 1);
90  }
91  else {
92  manual_->textureCoord(0, 1);
93  }
94  if (use_color) {
95  manual_->colour(color);
96  }
97  manual_->end();
98  node->attachObject(manual_);
99  }
100 
102  {
103  manual_->detachFromParent();
104  //manager_->destroyManualObject(manual_); // this crashes rviz
105  }
106 
107  CameraInfoDisplay::CameraInfoDisplay(): image_updated_(true)
108  {
110  // initialize properties
113  "far clip",
114  1.0,
115  "far clip distance from the origin of camera info",
116  this, SLOT(updateFarClipDistance()));
118  "show edges",
119  true,
120  "show edges of the region of the camera info",
121  this, SLOT(updateShowEdges()));
123  "show polygons",
124  true,
125  "show polygons of the region of the camera info",
126  this, SLOT(updateShowPolygons()));
128  "not show side polygons",
129  true,
130  "do not show polygons of the region of the camera info",
131  this, SLOT(updateNotShowSidePolygons()));
133  "use image",
134  false,
135  "use image as texture",
136  this, SLOT(updateUseImage()));
138  "Image Topic", "",
139  ros::message_traits::datatype<sensor_msgs::Image>(),
140  "sensor_msgs::Image topic to subscribe to.",
141  this, SLOT( updateImageTopic() ));
144  "transport hints",
145  "transport hint for image subscription",
146  this, SLOT( updateImageTopic() ));
148 
150  "color",
151  QColor(85, 255, 255),
152  "color of CameraInfo",
153  this, SLOT(updateColor()));
155  "edge color",
156  QColor(125, 125, 125),
157  "edge color of CameraInfo",
158  this, SLOT(updateEdgeColor()));
160  "alpha",
161  0.5,
162  "alpha blending value",
163  this, SLOT(updateAlpha()));
164  }
165 
167  {
168  if (edges_) {
169  edges_->clear();
170  }
171  polygons_.clear();
173  delete color_property_;
174  delete alpha_property_;
176  delete edge_color_property_;
177  }
178 
180  {
181  MFDClass::reset();
182  if (edges_) {
183  edges_->clear();
184  }
185  polygons_.clear();
186  camera_info_ = sensor_msgs::CameraInfo::ConstPtr(); // reset to NULL
187  }
188 
190  {
192  scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
193  updateColor();
194  updateAlpha();
198  updateShowEdges();
200  updateUseImage();
201  updateEdgeColor();
202  }
203 
205  const sensor_msgs::CameraInfo::ConstPtr& msg)
206  {
207  if (!isSameCameraInfo(msg)) {
209  }
210  // move scene_node according to tf
211  Ogre::Vector3 position;
212  Ogre::Quaternion quaternion;
213  std::string frame_id = msg->header.frame_id;
214  if (frame_id[0] == '/') {
215  frame_id = frame_id.substr(1, frame_id.size());
216  }
217  if(!context_->getFrameManager()->getTransform(frame_id,
218  msg->header.stamp,
219  position,
220  quaternion)) {
221  ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
222  qPrintable( getName() ), msg->header.frame_id.c_str(),
223  qPrintable( fixed_frame_ ));
224  }
225  scene_node_->setPosition(position);
226  scene_node_->setOrientation(quaternion);
227  camera_info_ = msg; // store for caching
228  }
229 
230  void CameraInfoDisplay::update(float wall_dt, float ros_dt)
231  {
232  boost::mutex::scoped_lock lock(mutex_);
233  if (image_updated_) {
234  ROS_DEBUG("image updated");
235  if (!bottom_texture_.isNull()) {
237  image_updated_ = false;
238  }
239  }
240  }
241 
243  const sensor_msgs::CameraInfo::ConstPtr& msg)
244  {
245  if (camera_info_) {
246  bool meta_same_p =
247  msg->header.frame_id == camera_info_->header.frame_id &&
248  msg->height == camera_info_->height &&
249  msg->width == camera_info_->width &&
250  msg->distortion_model == camera_info_->distortion_model &&
251  msg->roi.x_offset == camera_info_->roi.x_offset &&
252  msg->roi.y_offset == camera_info_->roi.y_offset &&
253  msg->roi.height == camera_info_->roi.height &&
254  msg->roi.width == camera_info_->roi.width;
255  if (meta_same_p) {
256  for (size_t i = 0; i < msg->P.size(); i++) {
257  if (msg->P[i] != camera_info_->P[i]) {
258  return false;
259  }
260  }
261  return true;
262  }
263  else {
264  return false;
265  }
266  }
267  else {
268  return false;
269  }
270  }
271 
273  const cv::Point3d& point)
274  {
275  Ogre::Vector3 p;
276  p[0] = point.x;
277  p[1] = point.y;
278  p[2] = point.z;
279  edges_->addPoint(p);
280  }
281 
283  const cv::Point3d& O, const cv::Point3d& A, const cv::Point3d& B, std::string name, bool use_color, bool upper_triangle)
284  {
285  Ogre::ColourValue color = rviz::qtToOgre(color_);
286  color.a = alpha_;
289  scene_node_,
290  O, A, B, name,
291  color,
292  use_color,
293  upper_triangle));
294  polygons_.push_back(triangle);
295  }
296 
297  void CameraInfoDisplay::createTextureForBottom(int width, int height)
298  {
299  if (bottom_texture_.isNull()
300  || bottom_texture_->getWidth() != width
301  || bottom_texture_->getHeight() != height) {
302  static uint32_t count = 0;
304  ss << "CameraInfoDisplayPolygonBottom" << count++;
306  = Ogre::MaterialManager::getSingleton().create(
307  ss.str(),
308  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
309  bottom_texture_ = Ogre::TextureManager::getSingleton().createManual(
310  material_bottom_->getName() + "Texture", // name
311  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
312  Ogre::TEX_TYPE_2D, width, height, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
313  material_bottom_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
314  Ogre::ColourValue color = rviz::qtToOgre(color_);
315  color.a = alpha_;
316  material_bottom_->getTechnique(0)->getPass(0)->setAmbient(color);
317  material_bottom_->setReceiveShadows(false);
318  material_bottom_->getTechnique(0)->setLightingEnabled(true);
319  material_bottom_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
320  material_bottom_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
321  material_bottom_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
322  material_bottom_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
323 
324  material_bottom_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
325  material_bottom_->getTechnique(0)->getPass(0)->createTextureUnitState(bottom_texture_->getName());
326  material_bottom_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
327  }
328  }
329 
331  {
332  if (texture_.isNull()) {
333  // material
334  static uint32_t count = 0;
336  ss << "CameraInfoDisplayPolygon" << count++;
337  material_
338  = Ogre::MaterialManager::getSingleton().create(
339  ss.str(),
340  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
341  texture_ = Ogre::TextureManager::getSingleton().createManual(
342  material_->getName() + "Texture", // name
343  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
344  Ogre::TEX_TYPE_2D, 1, 1, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
345  material_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
346  Ogre::ColourValue color = rviz::qtToOgre(color_);
347  color.a = alpha_;
348  material_->getTechnique(0)->getPass(0)->setAmbient(color);
349  material_->setReceiveShadows(false);
350  material_->getTechnique(0)->setLightingEnabled(true);
351  material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
352  material_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
353  material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
354  material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
355 
356  material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
357  material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_->getName());
358  material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
359  createTextureForBottom(640, 480);
360  }
361  }
362 
363  void CameraInfoDisplay::subscribeImage(std::string topic)
364  {
365 
367  if (topic.empty()) {
368  ROS_WARN("topic name is empty");
369  }
370  ros::NodeHandle nh;
374  }
375 
377  {
378  bottom_texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
379  const Ogre::PixelBox& pixelBox
380  = bottom_texture_->getBuffer()->getCurrentLock();
381  Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
382 
383  // Don't copy pixel-by-pixel image matrices.
384  // Just split matrix into channels, add needed alpha channel and merge back directly into buffer.
385  if (use_image_ && !image_.empty() &&
386  bottom_texture_->getHeight() == image_.rows &&
387  bottom_texture_->getWidth() == image_.cols) {
388  ROS_DEBUG("bottom_texture_->getHeight(): %u", bottom_texture_->getHeight());
389  ROS_DEBUG("bottom_texture_->getWidth(): %u", bottom_texture_->getWidth());
390  ROS_DEBUG("image_.rows: %d", image_.rows);
391  ROS_DEBUG("image_.cols: %d", image_.cols);
392 
393  std::vector<cv::Mat> splitted;
394  cv::split(image_, splitted);
395  // Swap channels RGB -> BGR for cv::merge.
396  std::swap(splitted[0], splitted[2]);
397  cv::Mat alpha(image_.rows, image_.cols, CV_8U, cv::Scalar(alpha_ * 255.0));
398  splitted.push_back(alpha);
399  cv::Mat boxMat(image_.rows, image_.cols, CV_8UC4, pDest);
400  cv::merge(splitted, boxMat);
401  } else {
402  memset(pDest, 0, bottom_texture_->getWidth() * bottom_texture_->getHeight());
403  QImage Hud(pDest, bottom_texture_->getWidth(), bottom_texture_->getHeight(), QImage::Format_ARGB32);
404  for (size_t j = 0; j < bottom_texture_->getHeight(); j++) {
405  for (size_t i = 0; i < bottom_texture_->getWidth(); i++) {
406  Hud.setPixel(i, j, color_.rgba());
407  }
408  }
409  }
410  bottom_texture_->getBuffer()->unlock();
411  }
412 
413  // convert sensor_msgs::Image into cv::Mat
415  const sensor_msgs::Image::ConstPtr& msg)
416  {
417  boost::mutex::scoped_lock lock(mutex_);
419  if (!camera_info_) {
420  return;
421  }
422  try
423  {
424  cv_ptr = cv_bridge::toCvShare(msg);
425  cv::Mat im = cv_ptr->image.clone();
426  if (msg->encoding == enc::BGRA8) {
427  cv::cvtColor(im, im, cv::COLOR_BGRA2RGB);
428  } else if (msg->encoding == enc::BGRA16) {
429  im.convertTo(im, CV_8U, 1 / 256.0);
430  cv::cvtColor(im, im, cv::COLOR_BGRA2RGB);
431  } else if (msg->encoding == enc::BGR8) {
432  cv::cvtColor(im, im, cv::COLOR_BGR2RGB);
433  } else if (msg->encoding == enc::BGR16) {
434  im.convertTo(im, CV_8U, 1 / 256.0);
435  cv::cvtColor(im, im, cv::COLOR_BGR2RGB);
436  } else if (msg->encoding == enc::RGBA8) {
437  cv::cvtColor(im, im, cv::COLOR_RGBA2RGB);
438  } else if (msg->encoding == enc::RGBA16) {
439  im.convertTo(im, CV_8U, 1 / 256.0);
440  cv::cvtColor(im, im, cv::COLOR_RGBA2RGB);
441  } else if (msg->encoding == enc::RGB8) {
442  // nothing
443  } else if (msg->encoding == enc::RGB16) {
444  im.convertTo(im, CV_8U, 1 / 256.0);
445  } else if (msg->encoding == enc::MONO8) {
446  cv::cvtColor(im, im, cv::COLOR_GRAY2RGB);
447  } else if (msg->encoding == enc::MONO16) {
448  im.convertTo(im, CV_8U, 1 / 256.0);
449  cv::cvtColor(im, im, cv::COLOR_GRAY2RGB);
450  } else {
451  ROS_ERROR("[CameraInfoDisplay] Not supported image encodings %s.", msg->encoding.c_str());
452  return;
453  }
454 
455  int roi_height = camera_info_->roi.height ? camera_info_->roi.height : camera_info_->height;
456  int roi_width = camera_info_->roi.width ? camera_info_->roi.width : camera_info_->width;
457  if (camera_info_->binning_y > 0) {
458  roi_height /= camera_info_->binning_y;
459  }
460  if (camera_info_->binning_x > 0) {
461  roi_width /= camera_info_->binning_x;
462  }
463 
464  if (im.cols == camera_info_->width && im.rows == camera_info_->height) {
465  cv::Rect roi(camera_info_->roi.x_offset, camera_info_->roi.y_offset,
466  camera_info_->roi.width ? camera_info_->roi.width : camera_info_->width,
467  camera_info_->roi.height ? camera_info_->roi.height : camera_info_->height);
468  image_ = cv::Mat(im, roi).clone();
469  } else if (im.cols == roi_width && im.rows == roi_height) {
470  image_ = im.clone();
471  } else {
472  ROS_ERROR("[CameraInfoDisplay] Invalid image size (w, h) = (%d, %d), expected (w, h) = (%d, %d) or (%d, %d) (ROI size)",
473  im.cols, im.rows,
474  camera_info_->width, camera_info_->height,
475  roi_width, roi_height);
476  return;
477  }
478 
479  // check the size of bottom texture
480  if (bottom_texture_.isNull()
481  || bottom_texture_->getWidth() != image_.cols
482  || bottom_texture_->getHeight() != image_.rows) {
484  if (camera_info_) {
486  }
487  }
488  image_updated_ = true;
489  }
490  catch (cv_bridge::Exception& e)
491  {
492  ROS_ERROR("cv_bridge exception: %s", e.what());
493  }
494  }
495 
497  const sensor_msgs::CameraInfo::ConstPtr& msg)
498  {
499  polygons_.clear();
500  if (edges_) {
501  edges_->clear();
502  }
504  bool model_success_p = model.fromCameraInfo(msg);
505  if (!model_success_p) {
506  setStatus(rviz::StatusProperty::Error, "Camera Info", "Failed to create camera model from msg");
507  ROS_ERROR("failed to create camera model");
508  return;
509  }
510  // fx and fy should not be equal 0.
511  if (model.fx() == 0.0 || model.fy() == 0.0) {
512  setStatus(rviz::StatusProperty::Error, "Camera Info", "Invalid intrinsic matrix");
513  ROS_ERROR_STREAM("camera model have invalid intrinsic matrix " << model.intrinsicMatrix());
514  return;
515  }
516  setStatus(rviz::StatusProperty::Ok, "Camera Info", "OK");
517 
519  // initialize BillboardLine
521  if (!edges_) {
523  scene_node_));
524  edges_->setLineWidth(0.01);
525  }
526 
527  int height = msg->roi.height ? msg->roi.height : msg->height;
528  int width = msg->roi.width ? msg->roi.width : msg->width;
529  if (msg->binning_y > 0) {
530  height /= msg->binning_y;
531  }
532  if (msg->binning_x > 0) {
533  width /= msg->binning_x;
534  }
535 
536  cv::Point2d a(0, 0), b(width, 0),
537  c(width, height), d(0, height);
538  // all the z = 1.0
539  cv::Point3d A = model.projectPixelTo3dRay(a);
540  cv::Point3d B = model.projectPixelTo3dRay(b);
541  cv::Point3d C = model.projectPixelTo3dRay(c);
542  cv::Point3d D = model.projectPixelTo3dRay(d);
543 
544  cv::Point3d scaled_A = A * far_clip_distance_;
545  cv::Point3d scaled_B = B * far_clip_distance_;
546  cv::Point3d scaled_C = C * far_clip_distance_;
547  cv::Point3d scaled_D = D * far_clip_distance_;
548 
549  cv::Point3d O(0, 0, 0);
550 
552  // build polygons
554  if (show_polygons_) {
556  // setup color for polygons
558  Ogre::ColourValue color = rviz::qtToOgre(color_);
559  color.a = alpha_;
560  prepareMaterial();
562  material_->getTechnique(0)->getPass(0)->setAmbient(color);
563  {
564  texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
565  const Ogre::PixelBox& pixelBox
566  = texture_->getBuffer()->getCurrentLock();
567  Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
568  memset(pDest, 0, 1);
569  QImage Hud(pDest, 1, 1, QImage::Format_ARGB32 );
570  Hud.setPixel(0, 0, color_.rgba());
571  texture_->getBuffer()->unlock();
572  }
573  addPolygon(O, scaled_B, scaled_A, material_->getName(), true, true);
574  addPolygon(O, scaled_C, scaled_B, material_->getName(), true, true);
575  addPolygon(O, scaled_D, scaled_C, material_->getName(), true, true);
576  addPolygon(O, scaled_A, scaled_D, material_->getName(), true, true);
577  }
578  // bottom
580 
581  addPolygon(scaled_A, scaled_B, scaled_D, material_bottom_->getName(), false, true);
582  addPolygon(scaled_B, scaled_C, scaled_D, material_bottom_->getName(), false, false);
583  }
585  // build edges
587  if (show_edges_) {
588  edges_->clear();
589  edges_->setMaxPointsPerLine(2);
590  edges_->setNumLines(8);
591  edges_->setColor(edge_color_.red() / 255.0,
592  edge_color_.green() / 255.0,
593  edge_color_.blue() / 255.0,
594  alpha_);
595  addPointToEdge(O); addPointToEdge(scaled_A); edges_->newLine();
596  addPointToEdge(O); addPointToEdge(scaled_B); edges_->newLine();
597  addPointToEdge(O); addPointToEdge(scaled_C); edges_->newLine();
598  addPointToEdge(O); addPointToEdge(scaled_D); edges_->newLine();
599  addPointToEdge(scaled_A); addPointToEdge(scaled_B); edges_->newLine();
600  addPointToEdge(scaled_B); addPointToEdge(scaled_C); edges_->newLine();
601  addPointToEdge(scaled_C); addPointToEdge(scaled_D); edges_->newLine();
602  addPointToEdge(scaled_D); addPointToEdge(scaled_A);
603  }
604  }
605 
607  // Properties updating functions
610  {
612  if (camera_info_) {
614  }
615  }
616 
618  {
620  if (camera_info_) {
622  }
623  }
624 
626  {
628  if (camera_info_) {
630  }
631  }
632 
634  {
636  if (camera_info_) {
638  }
639  }
640 
642  {
644  if (show_polygons_) {
646  }
647  else {
649  }
650  if (camera_info_) {
652  }
653  }
654 
656  {
658  if (camera_info_) {
660  }
661  }
662 
664  {
665  if (use_image_) {
666  std::string topic = image_topic_property_->getStdString();
667  subscribeImage(topic);
668  } else {
670  // Set image_updated_ true in order to clear the bottom texture in update() method.
671  image_updated_ = true;
672  }
673  }
674 
676  {
678  if (use_image_) {
681  }
682  else {
685  }
687  }
689  {
691  if (camera_info_) {
693  }
694  }
695 }
696 
697 
d
Definition: setup.py:6
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
virtual void addPointToEdge(const cv::Point3d &point)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::RosTopicProperty * image_topic_property_
DisplayContext * context_
virtual QColor getColor() const
image_transport::Subscriber image_sub_
sensor_msgs::CameraInfo::ConstPtr camera_info_
width
#define ROS_WARN(...)
Ogre::SceneNode * scene_node_
std::string getStdString()
virtual void createTextureForBottom(int width, int height)
Ogre::ColourValue qtToOgre(const QColor &c)
QString fixed_frame_
virtual void createCameraInfoShapes(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &msg)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
virtual QString getName() const
topic
virtual void update(float wall_dt, float ros_dt)
virtual FrameManager * getFrameManager() const=0
virtual void addPolygon(const cv::Point3d &O, const cv::Point3d &A, const cv::Point3d &B, std::string name, bool use_color, bool upper_triangle)
virtual bool isSameCameraInfo(const sensor_msgs::CameraInfo::ConstPtr &camera_info)
Ogre::SceneManager * scene_manager_
virtual Ogre::SceneManager * getSceneManager() const=0
ImageTransportHintsProperty * image_transport_hints_property_
virtual float getFloat() const
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
const cv::Matx33d & intrinsicMatrix() const
std::vector< TrianglePolygon::Ptr > polygons_
TrianglePolygon(Ogre::SceneManager *manager, Ogre::SceneNode *node, const cv::Point3d &O, const cv::Point3d &A, const cv::Point3d &B, const std::string &name, const Ogre::ColourValue &color, bool use_color, bool upper_triangle)
rviz::FloatProperty * far_clip_distance_property_
#define ROS_ERROR_STREAM(args)
height
virtual bool getBool() const
#define ROS_ERROR(...)
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual void subscribeImage(std::string topic)
virtual void processMessage(const sensor_msgs::CameraInfo::ConstPtr &msg)
rviz::BoolProperty * not_show_side_polygons_property_
#define ROS_DEBUG(...)


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