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/o2r 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>
44 
45 namespace jsk_rviz_plugins
46 {
48  Ogre::SceneManager* manager,
49  Ogre::SceneNode* node,
50  const cv::Point3d& O,
51  const cv::Point3d& A,
52  const cv::Point3d& B,
53  const std::string& name,
54  const Ogre::ColourValue& color,
55  bool use_color,
56  bool upper_triangle)
57  {
58  // uniq string is requred for name
59 
60  manual_ = manager->createManualObject();
61  manual_->clear();
62  manual_->begin(name,
63  Ogre::RenderOperation::OT_TRIANGLE_STRIP);
64  manual_->position(O.x, O.y, O.z);
65  if (upper_triangle) {
66  manual_->textureCoord(0, 0);
67  }
68  else {
69  manual_->textureCoord(1, 0);
70  }
71  if (use_color) {
72  manual_->colour(color);
73  }
74  manual_->position(A.x, A.y, A.z);
75  if (upper_triangle) {
76  manual_->textureCoord(1, 0);
77  }
78  else {
79  manual_->textureCoord(1, 1);
80  }
81  if (use_color) {
82  manual_->colour(color);
83  }
84  manual_->position(B.x, B.y, B.z);
85  if (upper_triangle) {
86  manual_->textureCoord(0, 1);
87  }
88  else {
89  manual_->textureCoord(0, 1);
90  }
91  if (use_color) {
92  manual_->colour(color);
93  }
94  manual_->end();
95  node->attachObject(manual_);
96  }
97 
99  {
100  manual_->detachFromParent();
101  //manager_->destroyManualObject(manual_); // this crashes rviz
102  }
103 
104  CameraInfoDisplay::CameraInfoDisplay(): image_updated_(true)
105  {
107  // initialize properties
110  "far clip",
111  1.0,
112  "far clip distance from the origin of camera info",
113  this, SLOT(updateFarClipDistance()));
115  "show edges",
116  true,
117  "show edges of the region of the camera info",
118  this, SLOT(updateShowEdges()));
120  "show polygons",
121  true,
122  "show polygons of the region of the camera info",
123  this, SLOT(updateShowPolygons()));
125  "not show side polygons",
126  true,
127  "do not show polygons of the region of the camera info",
128  this, SLOT(updateNotShowSidePolygons()));
130  "use image",
131  false,
132  "use image as texture",
133  this, SLOT(updateUseImage()));
135  "Image Topic", "",
136  ros::message_traits::datatype<sensor_msgs::Image>(),
137  "sensor_msgs::Image topic to subscribe to.",
138  this, SLOT( updateImageTopic() ));
141  "transport hints",
142  "transport hint for image subscription",
143  this, SLOT( updateImageTopic() ));
145 
147  "color",
148  QColor(85, 255, 255),
149  "color of CameraInfo",
150  this, SLOT(updateColor()));
152  "edge color",
153  QColor(125, 125, 125),
154  "edge color of CameraInfo",
155  this, SLOT(updateEdgeColor()));
157  "alpha",
158  0.5,
159  "alpha blending value",
160  this, SLOT(updateAlpha()));
161  }
162 
164  {
165  if (edges_) {
166  edges_->clear();
167  }
168  polygons_.clear();
170  delete color_property_;
171  delete alpha_property_;
173  delete edge_color_property_;
174  }
175 
177  {
178  MFDClass::reset();
179  if (edges_) {
180  edges_->clear();
181  }
182  polygons_.clear();
183  camera_info_ = sensor_msgs::CameraInfo::ConstPtr(); // reset to NULL
184  }
185 
187  {
189  scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
190  updateColor();
191  updateAlpha();
195  updateShowEdges();
197  updateUseImage();
198  updateEdgeColor();
199  }
200 
202  const sensor_msgs::CameraInfo::ConstPtr& msg)
203  {
204  if (!isSameCameraInfo(msg)) {
206  }
207  // move scene_node according to tf
208  Ogre::Vector3 position;
209  Ogre::Quaternion quaternion;
210  if(!context_->getFrameManager()->getTransform(msg->header.frame_id,
211  msg->header.stamp,
212  position,
213  quaternion)) {
214  ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
215  qPrintable( getName() ), msg->header.frame_id.c_str(),
216  qPrintable( fixed_frame_ ));
217  }
218  scene_node_->setPosition(position);
219  scene_node_->setOrientation(quaternion);
220  camera_info_ = msg; // store for caching
221  }
222 
223  void CameraInfoDisplay::update(float wall_dt, float ros_dt)
224  {
225  boost::mutex::scoped_lock lock(mutex_);
226  if (image_updated_) {
227  ROS_DEBUG("image updated");
228  if (!bottom_texture_.isNull()) {
230  image_updated_ = false;
231  }
232  }
233  }
234 
236  const sensor_msgs::CameraInfo::ConstPtr& msg)
237  {
238  if (camera_info_) {
239  bool meta_same_p =
240  msg->header.frame_id == camera_info_->header.frame_id &&
241  msg->height == camera_info_->height &&
242  msg->width == camera_info_->width &&
243  msg->distortion_model == camera_info_->distortion_model;
244  if (meta_same_p) {
245  for (size_t i = 0; i < msg->P.size(); i++) {
246  if (msg->P[i] != camera_info_->P[i]) {
247  return false;
248  }
249  }
250  return true;
251  }
252  else {
253  return false;
254  }
255  }
256  else {
257  return false;
258  }
259  }
260 
262  const cv::Point3d& point)
263  {
264  Ogre::Vector3 p;
265  p[0] = point.x;
266  p[1] = point.y;
267  p[2] = point.z;
268  edges_->addPoint(p);
269  }
270 
272  const cv::Point3d& O, const cv::Point3d& A, const cv::Point3d& B, std::string name, bool use_color, bool upper_triangle)
273  {
274  Ogre::ColourValue color = rviz::qtToOgre(color_);
275  color.a = alpha_;
278  scene_node_,
279  O, A, B, name,
280  color,
281  use_color,
282  upper_triangle));
283  polygons_.push_back(triangle);
284  }
285 
286  void CameraInfoDisplay::createTextureForBottom(int width, int height)
287  {
288  if (bottom_texture_.isNull()
289  || bottom_texture_->getWidth() != width
290  || bottom_texture_->getHeight() != height) {
291  static uint32_t count = 0;
293  ss << "CameraInfoDisplayPolygonBottom" << count++;
295  = Ogre::MaterialManager::getSingleton().create(
296  ss.str(),
297  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
298  bottom_texture_ = Ogre::TextureManager::getSingleton().createManual(
299  material_bottom_->getName() + "Texture", // name
300  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
301  Ogre::TEX_TYPE_2D, width, height, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
302  material_bottom_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
303  Ogre::ColourValue color = rviz::qtToOgre(color_);
304  color.a = alpha_;
305  material_bottom_->getTechnique(0)->getPass(0)->setAmbient(color);
306  material_bottom_->setReceiveShadows(false);
307  material_bottom_->getTechnique(0)->setLightingEnabled(true);
308  material_bottom_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
309  material_bottom_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
310  material_bottom_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
311  material_bottom_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
312 
313  material_bottom_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
314  material_bottom_->getTechnique(0)->getPass(0)->createTextureUnitState(bottom_texture_->getName());
315  material_bottom_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
316  }
317  }
318 
320  {
321  if (texture_.isNull()) {
322  // material
323  static uint32_t count = 0;
325  ss << "CameraInfoDisplayPolygon" << count++;
326  material_
327  = Ogre::MaterialManager::getSingleton().create(
328  ss.str(),
329  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
330  texture_ = Ogre::TextureManager::getSingleton().createManual(
331  material_->getName() + "Texture", // name
332  Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
333  Ogre::TEX_TYPE_2D, 1, 1, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
334  material_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
335  Ogre::ColourValue color = rviz::qtToOgre(color_);
336  color.a = alpha_;
337  material_->getTechnique(0)->getPass(0)->setAmbient(color);
338  material_->setReceiveShadows(false);
339  material_->getTechnique(0)->setLightingEnabled(true);
340  material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
341  material_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
342  material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
343  material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
344 
345  material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
346  material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_->getName());
347  material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
348  createTextureForBottom(640, 480);
349  }
350  }
351 
352  void CameraInfoDisplay::subscribeImage(std::string topic)
353  {
354 
356  if (topic.empty()) {
357  ROS_WARN("topic name is empty");
358  }
359  ros::NodeHandle nh;
363  }
364 
366  {
367  bottom_texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
368  const Ogre::PixelBox& pixelBox
369  = bottom_texture_->getBuffer()->getCurrentLock();
370  Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
371 
372  // Don't copy pixel-by-pixel image matrices.
373  // Just split matrix into channels, add needed alpha channel and merge back directly into buffer.
374  if (use_image_ && !image_.empty() &&
375  bottom_texture_->getHeight() == image_.rows &&
376  bottom_texture_->getWidth() == image_.cols) {
377  ROS_DEBUG("bottom_texture_->getHeight(): %u", bottom_texture_->getHeight());
378  ROS_DEBUG("bottom_texture_->getWidth(): %u", bottom_texture_->getWidth());
379  ROS_DEBUG("image_.rows: %d", image_.rows);
380  ROS_DEBUG("image_.cols: %d", image_.cols);
381 
382  std::vector<cv::Mat> splitted;
383  cv::split(image_, splitted);
384  // Swap channels RGB -> BGR for cv::merge.
385  std::swap(splitted[0], splitted[2]);
386  cv::Mat alpha(image_.rows, image_.cols, CV_8U, cv::Scalar(alpha_ * 255.0));
387  splitted.push_back(alpha);
388  cv::Mat boxMat(image_.rows, image_.cols, CV_8UC4, pDest);
389  cv::merge(splitted, boxMat);
390  } else {
391  memset(pDest, 0, bottom_texture_->getWidth() * bottom_texture_->getHeight());
392  QImage Hud(pDest, bottom_texture_->getWidth(), bottom_texture_->getHeight(), QImage::Format_ARGB32);
393  for (size_t j = 0; j < bottom_texture_->getHeight(); j++) {
394  for (size_t i = 0; i < bottom_texture_->getWidth(); i++) {
395  Hud.setPixel(i, j, color_.rgba());
396  }
397  }
398  }
399  bottom_texture_->getBuffer()->unlock();
400  }
401 
402  // convert sensor_msgs::Image into cv::Mat
404  const sensor_msgs::Image::ConstPtr& msg)
405  {
406  boost::mutex::scoped_lock lock(mutex_);
407  cv_bridge::CvImagePtr cv_ptr;
408  try
409  {
411  image_ = cv_ptr->image;
412  // check the size of bottom texture
413  if (bottom_texture_.isNull()
414  || bottom_texture_->getWidth() != image_.cols
415  || bottom_texture_->getHeight() != image_.rows) {
417  if (camera_info_) {
419  }
420  }
421  image_updated_ = true;
422  }
423  catch (cv_bridge::Exception& e)
424  {
425  ROS_ERROR("cv_bridge exception: %s", e.what());
426  }
427  }
428 
430  const sensor_msgs::CameraInfo::ConstPtr& msg)
431  {
432  polygons_.clear();
433  if (edges_) {
434  edges_->clear();
435  }
437  bool model_success_p = model.fromCameraInfo(msg);
438  if (!model_success_p) {
439  setStatus(rviz::StatusProperty::Error, "Camera Info", "Failed to create camera model from msg");
440  ROS_ERROR("failed to create camera model");
441  return;
442  }
443  // fx and fy should not be equal 0.
444  if (model.fx() == 0.0 || model.fy() == 0.0) {
445  setStatus(rviz::StatusProperty::Error, "Camera Info", "Invalid intrinsic matrix");
446  ROS_ERROR_STREAM("camera model have invalid intrinsic matrix " << model.intrinsicMatrix());
447  return;
448  }
449  setStatus(rviz::StatusProperty::Ok, "Camera Info", "OK");
450 
452  // initialize BillboardLine
454  if (!edges_) {
456  scene_node_));
457  edges_->setLineWidth(0.01);
458  }
459 
460  cv::Point2d a(0, 0), b(msg->width, 0),
461  c(msg->width, msg->height), d(0, msg->height);
462  // all the z = 1.0
463  cv::Point3d A = model.projectPixelTo3dRay(a);
464  cv::Point3d B = model.projectPixelTo3dRay(b);
465  cv::Point3d C = model.projectPixelTo3dRay(c);
466  cv::Point3d D = model.projectPixelTo3dRay(d);
467 
468  cv::Point3d scaled_A = A * far_clip_distance_;
469  cv::Point3d scaled_B = B * far_clip_distance_;
470  cv::Point3d scaled_C = C * far_clip_distance_;
471  cv::Point3d scaled_D = D * far_clip_distance_;
472 
473  cv::Point3d O(0, 0, 0);
474 
476  // build polygons
478  if (show_polygons_) {
480  // setup color for polygons
482  Ogre::ColourValue color = rviz::qtToOgre(color_);
483  color.a = alpha_;
484  prepareMaterial();
486  material_->getTechnique(0)->getPass(0)->setAmbient(color);
487  {
488  texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
489  const Ogre::PixelBox& pixelBox
490  = texture_->getBuffer()->getCurrentLock();
491  Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
492  memset(pDest, 0, 1);
493  QImage Hud(pDest, 1, 1, QImage::Format_ARGB32 );
494  Hud.setPixel(0, 0, color_.rgba());
495  texture_->getBuffer()->unlock();
496  }
497  addPolygon(O, scaled_B, scaled_A, material_->getName(), true, true);
498  addPolygon(O, scaled_C, scaled_B, material_->getName(), true, true);
499  addPolygon(O, scaled_D, scaled_C, material_->getName(), true, true);
500  addPolygon(O, scaled_A, scaled_D, material_->getName(), true, true);
501  }
502  // bottom
504 
505  addPolygon(scaled_A, scaled_B, scaled_D, material_bottom_->getName(), false, true);
506  addPolygon(scaled_B, scaled_C, scaled_D, material_bottom_->getName(), false, false);
507  }
509  // build edges
511  if (show_edges_) {
512  edges_->clear();
513  edges_->setMaxPointsPerLine(2);
514  edges_->setNumLines(8);
515  edges_->setColor(edge_color_.red() / 255.0,
516  edge_color_.green() / 255.0,
517  edge_color_.blue() / 255.0,
518  alpha_);
519  addPointToEdge(O); addPointToEdge(scaled_A); edges_->newLine();
520  addPointToEdge(O); addPointToEdge(scaled_B); edges_->newLine();
521  addPointToEdge(O); addPointToEdge(scaled_C); edges_->newLine();
522  addPointToEdge(O); addPointToEdge(scaled_D); edges_->newLine();
523  addPointToEdge(scaled_A); addPointToEdge(scaled_B); edges_->newLine();
524  addPointToEdge(scaled_B); addPointToEdge(scaled_C); edges_->newLine();
525  addPointToEdge(scaled_C); addPointToEdge(scaled_D); edges_->newLine();
526  addPointToEdge(scaled_D); addPointToEdge(scaled_A);
527  }
528  }
529 
531  // Properties updating functions
534  {
536  if (camera_info_) {
538  }
539  }
540 
542  {
544  if (camera_info_) {
546  }
547  }
548 
550  {
552  if (camera_info_) {
554  }
555  }
556 
558  {
560  if (camera_info_) {
562  }
563  }
564 
566  {
568  if (show_polygons_) {
570  }
571  else {
573  }
574  if (camera_info_) {
576  }
577  }
578 
580  {
582  if (camera_info_) {
584  }
585  }
586 
588  {
589  if (use_image_) {
590  std::string topic = image_topic_property_->getStdString();
591  subscribeImage(topic);
592  } else {
594  // Set image_updated_ true in order to clear the bottom texture in update() method.
595  image_updated_ = true;
596  }
597  }
598 
600  {
602  if (use_image_) {
605  }
606  else {
609  }
611  }
613  {
615  if (camera_info_) {
617  }
618  }
619 }
620 
621 
virtual QColor getColor() const
d
Definition: setup.py:6
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())
const cv::Matx33d & intrinsicMatrix() const
virtual void addPointToEdge(const cv::Point3d &point)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
rviz::RosTopicProperty * image_topic_property_
DisplayContext * context_
cv::Point3d projectPixelTo3dRay(const cv::Point2d &uv_rect) const
image_transport::Subscriber image_sub_
virtual float getFloat() const
sensor_msgs::CameraInfo::ConstPtr camera_info_
#define ROS_WARN(...)
Ogre::SceneNode * scene_node_
std::string getStdString()
virtual void createTextureForBottom(int width, int height)
Ogre::ColourValue qtToOgre(const QColor &c)
virtual bool getBool() const
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)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
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_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
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)
#define ROS_ERROR(...)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual void subscribeImage(std::string topic)
virtual QString getName() const
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 Sat Mar 20 2021 03:03:18