selection_manager.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 <algorithm>
31 
32 #include <QTimer>
33 
34 #include <OgreCamera.h>
35 #include <OgreEntity.h>
36 #include <OgreHardwarePixelBuffer.h>
37 #include <OgreManualObject.h>
38 #include <OgreMaterialManager.h>
39 #include <OgreRenderSystem.h>
40 #include <OgreRenderTexture.h>
41 #include <OgreRoot.h>
42 #include <OgreSceneManager.h>
43 #include <OgreSceneNode.h>
44 #include <OgreSubEntity.h>
45 #include <OgreTextureManager.h>
46 #include <OgreViewport.h>
47 #include <OgreWireBoundingBox.h>
48 #include <OgreSharedPtr.h>
49 #include <OgreTechnique.h>
50 #include <OgreRectangle2D.h>
51 
53 #include <sensor_msgs/Image.h>
54 
55 #include <ros/assert.h>
56 #include <ros/node_handle.h>
57 #include <ros/publisher.h>
58 
60 #include <rviz/ogre_helpers/axes.h>
67 #include <rviz/render_panel.h>
68 #include <rviz/view_controller.h>
69 #include <rviz/view_manager.h>
71 
73 #include <vector>
74 
75 
76 namespace rviz
77 {
79  : vis_manager_(manager)
80  , highlight_enabled_(false)
81  , uid_counter_(0)
82  , interaction_enabled_(false)
83  , debug_mode_(false)
84  , property_model_(new PropertyTreeModel(new Property("root")))
85 {
86  for (uint32_t i = 0; i < s_num_render_textures_; ++i)
87  {
88  pixel_boxes_[i].data = nullptr;
89  }
90  depth_pixel_box_.data = nullptr;
91 
92  QTimer* timer = new QTimer(this);
93  connect(timer, &QTimer::timeout, this, &SelectionManager::updateProperties);
94  timer->start(200);
95 }
96 
98 {
99  boost::recursive_mutex::scoped_lock lock(global_mutex_);
100 
102 
104  delete highlight_rectangle_;
105 
106  for (uint32_t i = 0; i < s_num_render_textures_; ++i)
107  {
108  delete[](uint8_t*) pixel_boxes_[i].data;
109  }
110  delete[](uint8_t*) depth_pixel_box_.data;
111 
112  vis_manager_->getSceneManager()->destroyCamera(camera_);
113 
114  delete property_model_;
115 }
116 
118 {
119  debug_mode_ = debug;
120 }
121 
123 {
124  // Create our render textures
125  setTextureSize(1);
126 
127  // Create our highlight rectangle
128  Ogre::SceneManager* scene_manager = vis_manager_->getSceneManager();
129  highlight_node_ = scene_manager->getRootSceneNode()->createChildSceneNode();
130 
131  std::stringstream ss;
132  static int count = 0;
133  ss << "SelectionRect" << count++;
134  highlight_rectangle_ = new Ogre::Rectangle2D(true);
135 
136  const static uint32_t texture_data[1] = {0xffff0080};
137  Ogre::DataStreamPtr pixel_stream;
138  pixel_stream.bind(new Ogre::MemoryDataStream((void*)&texture_data[0], 4));
139 
140  Ogre::TexturePtr tex = Ogre::TextureManager::getSingleton().loadRawData(
141  ss.str() + "Texture", Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, pixel_stream, 1, 1,
142  Ogre::PF_R8G8B8A8, Ogre::TEX_TYPE_2D, 0);
143 
144  Ogre::MaterialPtr material = Ogre::MaterialManager::getSingleton().create(
145  ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
146  material->setLightingEnabled(false);
147  // material->getTechnique(0)->getPass(0)->setPolygonMode(Ogre::PM_WIREFRAME);
148  setMaterial(*highlight_rectangle_, material);
149  Ogre::AxisAlignedBox aabInf;
150  aabInf.setInfinite();
151  highlight_rectangle_->setBoundingBox(aabInf);
152  highlight_rectangle_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
153  material->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
154  material->setCullingMode(Ogre::CULL_NONE);
155 
156  Ogre::TextureUnitState* tex_unit = material->getTechnique(0)->getPass(0)->createTextureUnitState();
157  tex_unit->setTextureName(tex->getName());
158  tex_unit->setTextureFiltering(Ogre::TFO_NONE);
159 
160  highlight_node_->attachObject(highlight_rectangle_);
161 
162  // create picking camera
163  camera_ = scene_manager->createCamera(ss.str() + "_camera");
164 
165  // create fallback picking material
166  fallback_pick_material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/DefaultPickAndDepth");
167  fallback_pick_material_->load();
168 
169  fallback_pick_cull_technique_ = fallback_pick_material_->getTechnique("PickCull");
170  fallback_black_cull_technique_ = fallback_pick_material_->getTechnique("BlackCull");
171  fallback_depth_cull_technique_ = fallback_pick_material_->getTechnique("DepthCull");
172 
173  fallback_pick_technique_ = fallback_pick_material_->getTechnique("Pick");
174  fallback_black_technique_ = fallback_pick_material_->getTechnique("Black");
175  fallback_depth_technique_ = fallback_pick_material_->getTechnique("Depth");
176 }
177 
178 
179 bool SelectionManager::get3DPoint(Ogre::Viewport* viewport, int x, int y, Ogre::Vector3& result_point)
180 {
181  ROS_DEBUG("SelectionManager.get3DPoint()");
182 
183  std::vector<Ogre::Vector3> result_points_temp;
184  bool success = get3DPatch(viewport, x, y, 1, 1, true, result_points_temp);
185  if (result_points_temp.empty())
186  {
187  // return result_point unmodified if get point fails.
188  return false;
189  }
190  result_point = result_points_temp[0];
191 
192  return success;
193 }
194 
195 
196 bool SelectionManager::getPatchDepthImage(Ogre::Viewport* viewport,
197  int x,
198  int y,
199  unsigned width,
200  unsigned height,
201  std::vector<float>& depth_vector)
202 {
203  unsigned int num_pixels = width * height;
204  depth_vector.reserve(num_pixels);
205 
206  setDepthTextureSize(width, height);
207 
208 
209  M_CollisionObjectToSelectionHandler::iterator handler_it = objects_.begin();
210  M_CollisionObjectToSelectionHandler::iterator handler_end = objects_.end();
211 
212  for (; handler_it != handler_end; ++handler_it)
213  {
214  handler_it->second->preRenderPass(0);
215  }
216 
217  if (render(viewport, depth_render_texture_, x, y, x + width, y + height, depth_pixel_box_, "Depth",
219  {
220  uint8_t* data_ptr = (uint8_t*)depth_pixel_box_.data;
221 
222  for (uint32_t pixel = 0; pixel < num_pixels; ++pixel)
223  {
224  uint8_t a = data_ptr[4 * pixel];
225  uint8_t b = data_ptr[4 * pixel + 1];
226  uint8_t c = data_ptr[4 * pixel + 2];
227 
228  int int_depth = (c << 16) | (b << 8) | a;
229  float normalized_depth = ((float)int_depth) / (float)0xffffff;
230  depth_vector.push_back(normalized_depth * camera_->getFarClipDistance());
231  }
232  }
233  else
234  {
235  ROS_WARN("Failed to render depth patch\n");
236  return false;
237  }
238 
239  handler_it = objects_.begin();
240  handler_end = objects_.end();
241  for (; handler_it != handler_end; ++handler_it)
242  {
243  handler_it->second->postRenderPass(0);
244  }
245 
246  return true;
247 }
248 
249 
250 bool SelectionManager::get3DPatch(Ogre::Viewport* viewport,
251  int x,
252  int y,
253  unsigned width,
254  unsigned height,
255  bool skip_missing,
256  std::vector<Ogre::Vector3>& result_points)
257 {
258  boost::recursive_mutex::scoped_lock lock(global_mutex_);
259  ROS_DEBUG("SelectionManager.get3DPatch()");
260 
261  std::vector<float> depth_vector;
262 
263 
264  if (!getPatchDepthImage(viewport, x, y, width, height, depth_vector))
265  return false;
266 
267 
268  unsigned int pixel_counter = 0;
269  Ogre::Matrix4 projection = camera_->getProjectionMatrix();
270  float depth;
271 
272  for (unsigned y_iter = 0; y_iter < height; ++y_iter)
273  for (unsigned x_iter = 0; x_iter < width; ++x_iter)
274  {
275  depth = depth_vector[pixel_counter];
276 
277  // Deal with missing or invalid points
278  if ((depth > camera_->getFarClipDistance()) || (depth == 0))
279  {
280  ++pixel_counter;
281  if (!skip_missing)
282  {
283  result_points.push_back(Ogre::Vector3(NAN, NAN, NAN));
284  }
285  continue;
286  }
287 
288 
289  Ogre::Vector3 result_point;
290  // We want to shoot rays through the center of pixels, not the corners,
291  // so add .5 pixels to the x and y coordinate to get to the center
292  // instead of the top left of the pixel.
293  Ogre::Real screenx = float(x_iter + .5) / float(width);
294  Ogre::Real screeny = float(y_iter + .5) / float(height);
295  if (projection[3][3] == 0.0) // If this is a perspective projection
296  {
297  // get world-space ray from camera & mouse coord
298  Ogre::Ray vp_ray = camera_->getCameraToViewportRay(screenx, screeny);
299 
300  // transform ray direction back into camera coords
301  Ogre::Vector3 dir_cam = camera_->getDerivedOrientation().Inverse() * vp_ray.getDirection();
302 
303  // normalize, so dir_cam.z == -depth
304  dir_cam = dir_cam / dir_cam.z * depth * -1;
305 
306  // compute 3d point from camera origin and direction*/
307  result_point = camera_->getDerivedPosition() + camera_->getDerivedOrientation() * dir_cam;
308  }
309  else // else this must be an orthographic projection.
310  {
311  // For orthographic projection, getCameraToViewportRay() does
312  // the right thing for us, and the above math does not work.
313  Ogre::Ray ray;
314  camera_->getCameraToViewportRay(screenx, screeny, &ray);
315 
316  result_point = ray.getPoint(depth);
317  }
318 
319  result_points.push_back(result_point);
320  ++pixel_counter;
321  }
322 
323  return !result_points.empty();
324 }
325 
326 
327 void SelectionManager::setDepthTextureSize(unsigned width, unsigned height)
328 {
329  // Cap and store requested texture size
330  // It's probably an error if an invalid size is requested.
331  if (width > 1024)
332  {
333  width = 1024;
334  ROS_ERROR_STREAM("SelectionManager::setDepthTextureSize invalid width requested. Max Width: 1024 -- "
335  "Width requested: "
336  << width << ". Capping Width at 1024.");
337  }
338 
339  if (depth_texture_width_ != width)
340  depth_texture_width_ = width;
341 
342  if (height > 1024)
343  {
344  height = 1024;
345  ROS_ERROR_STREAM("SelectionManager::setDepthTextureSize invalid height requested. Max Height: 1024 "
346  "-- Height requested: "
347  << width << ". Capping Height at 1024.");
348  }
349 
350  if (depth_texture_height_ != height)
351  depth_texture_height_ = height;
352 
353  if (!depth_render_texture_.get() || depth_render_texture_->getWidth() != width ||
354  depth_render_texture_->getHeight() != height)
355  {
356  std::string tex_name = "DepthTexture";
357  if (depth_render_texture_.get())
358  {
359  tex_name = depth_render_texture_->getName();
360 
361  // destroy old
362  Ogre::TextureManager::getSingleton().remove(tex_name);
363  }
364 
365  depth_render_texture_ = Ogre::TextureManager::getSingleton().createManual(
366  tex_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D,
367  depth_texture_width_, depth_texture_height_, 0, Ogre::PF_R8G8B8, Ogre::TU_RENDERTARGET);
368 
369  Ogre::RenderTexture* render_texture = depth_render_texture_->getBuffer()->getRenderTarget();
370  render_texture->setAutoUpdated(false);
371  }
372 }
373 
374 
376 {
377  if (size > 1024)
378  {
379  size = 1024;
380  }
381 
382  texture_size_ = size;
383 
384  for (uint32_t pass = 0; pass < s_num_render_textures_; ++pass)
385  {
386  // check if we need to change the texture size
387  if (!render_textures_[pass].get() || render_textures_[pass]->getWidth() != size)
388  {
389  std::string tex_name;
390  if (render_textures_[pass].get())
391  {
392  tex_name = render_textures_[pass]->getName();
393 
394  // destroy old
395  Ogre::TextureManager::getSingleton().remove(tex_name);
396  }
397  else
398  {
399  std::stringstream ss;
400  static int count = 0;
401  ss << "SelectionTexture" << count++;
402  tex_name = ss.str();
403  }
404 
405  // create new texture
406  render_textures_[pass] = Ogre::TextureManager::getSingleton().createManual(
407  tex_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, size,
408  size, 0, Ogre::PF_R8G8B8, Ogre::TU_STATIC | Ogre::TU_RENDERTARGET);
409 
410  Ogre::RenderTexture* render_texture = render_textures_[pass]->getBuffer()->getRenderTarget();
411  render_texture->setAutoUpdated(false);
412  }
413  }
414 }
415 
417 {
418  boost::recursive_mutex::scoped_lock lock(global_mutex_);
419 
420  objects_.clear();
421 }
422 
424 {
425  interaction_enabled_ = enable;
426  M_CollisionObjectToSelectionHandler::iterator handler_it = objects_.begin();
427  M_CollisionObjectToSelectionHandler::iterator handler_end = objects_.end();
428  for (; handler_it != handler_end; ++handler_it)
429  {
430  if (InteractiveObjectPtr object = handler_it->second->getInteractiveObject().lock())
431  {
432  object->enableInteraction(enable);
433  }
434  }
435 }
436 
438 {
439  uid_counter_++;
440  if (uid_counter_ > 0x00ffffff)
441  {
442  uid_counter_ = 0;
443  }
444 
445  uint32_t handle = 0;
446 
447  // shuffle around the bits so we get lots of colors
448  // when we're displaying the selection buffer
449  for (unsigned int i = 0; i < 24; i++)
450  {
451  uint32_t shift = (((23 - i) % 3) * 8) + (23 - i) / 3;
452  uint32_t bit = ((uint32_t)(uid_counter_ >> i) & (uint32_t)1) << shift;
453  handle |= bit;
454  }
455 
456  return handle;
457 }
458 
460 {
461  if (!obj)
462  {
463  // ROS_BREAK();
464  return;
465  }
466 
467  boost::recursive_mutex::scoped_lock lock(global_mutex_);
468 
469  InteractiveObjectPtr object = handler->getInteractiveObject().lock();
470  if (object)
471  {
472  object->enableInteraction(interaction_enabled_);
473  }
474 
475  bool inserted = objects_.insert(std::make_pair(obj, handler)).second;
476  ROS_ASSERT(inserted);
477  Q_UNUSED(inserted);
478 }
479 
481 {
482  if (!obj)
483  {
484  return;
485  }
486 
487  boost::recursive_mutex::scoped_lock lock(global_mutex_);
488 
489  M_Picked::iterator it = selection_.find(obj);
490  if (it != selection_.end())
491  {
492  M_Picked objs;
493  objs.insert(std::make_pair(it->first, it->second));
494 
495  removeSelection(objs);
496  }
497 
498  objects_.erase(obj);
499 }
500 
502 {
503  boost::recursive_mutex::scoped_lock lock(global_mutex_);
504 
505  highlight_node_->setVisible(highlight_enabled_);
506 
507  if (highlight_enabled_)
508  {
510 
511 #if 0
512  M_Picked results;
513  highlight_node_->setVisible(false);
515  highlight_node_->setVisible(true);
516 #endif
517  }
518 }
519 
520 void SelectionManager::highlight(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2)
521 {
522  boost::recursive_mutex::scoped_lock lock(global_mutex_);
523 
524  highlight_enabled_ = true;
525 
526  highlight_.viewport = viewport;
527  highlight_.x1 = x1;
528  highlight_.y1 = y1;
529  highlight_.x2 = x2;
530  highlight_.y2 = y2;
531 }
532 
534 {
535  boost::recursive_mutex::scoped_lock lock(global_mutex_);
536 
537  highlight_enabled_ = false;
538 }
539 
540 void SelectionManager::select(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, SelectType type)
541 {
542  boost::recursive_mutex::scoped_lock lock(global_mutex_);
543 
544  highlight_enabled_ = false;
545  highlight_node_->setVisible(false);
546 
547  M_Picked results;
548  pick(viewport, x1, y1, x2, y2, results);
549 
550  if (type == Add)
551  {
552  addSelection(results);
553  }
554  else if (type == Remove)
555  {
556  removeSelection(results);
557  }
558  else if (type == Replace)
559  {
560  setSelection(results);
561  }
562 }
563 
564 void SelectionManager::setHighlightRect(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2)
565 {
566  float nx1 = ((float)x1 / viewport->getActualWidth()) * 2 - 1;
567  float nx2 = ((float)x2 / viewport->getActualWidth()) * 2 - 1;
568  float ny1 = -(((float)y1 / viewport->getActualHeight()) * 2 - 1);
569  float ny2 = -(((float)y2 / viewport->getActualHeight()) * 2 - 1);
570 
571  nx1 = nx1 < -1 ? -1 : (nx1 > 1 ? 1 : nx1);
572  ny1 = ny1 < -1 ? -1 : (ny1 > 1 ? 1 : ny1);
573  nx2 = nx2 < -1 ? -1 : (nx2 > 1 ? 1 : nx2);
574  ny2 = ny2 < -1 ? -1 : (ny2 > 1 ? 1 : ny2);
575 
576  highlight_rectangle_->setCorners(nx1, ny1, nx2, ny2);
577 }
578 
579 void SelectionManager::unpackColors(Ogre::PixelBox& box, V_CollObject& pixels)
580 {
581  int w = box.getWidth();
582  int h = box.getHeight();
583 
584  pixels.clear();
585  pixels.reserve(w * h);
586  size_t size = Ogre::PixelUtil::getMemorySize(1, 1, 1, box.format);
587 
588  for (int y = 0; y < h; y++)
589  {
590  for (int x = 0; x < w; x++)
591  {
592  uint32_t pos = (x + y * w) * size;
593  uint32_t pix_val = 0;
594  memcpy((uint8_t*)&pix_val, (uint8_t*)box.data + pos, size);
595  pixels.push_back(colorToHandle(box.format, pix_val));
596  }
597  }
598 }
599 
600 void SelectionManager::renderAndUnpack(Ogre::Viewport* viewport,
601  uint32_t pass,
602  int x1,
603  int y1,
604  int x2,
605  int y2,
606  V_CollObject& pixels)
607 {
609 
610  std::stringstream scheme;
611  scheme << "Pick";
612  if (pass > 0)
613  {
614  scheme << pass;
615  }
616 
617  if (render(viewport, render_textures_[pass], x1, y1, x2, y2, pixel_boxes_[pass], scheme.str(),
619  {
620  unpackColors(pixel_boxes_[pass], pixels);
621  }
622 }
623 
624 
625 bool SelectionManager::render(Ogre::Viewport* viewport,
626  const Ogre::TexturePtr& tex,
627  int x1,
628  int y1,
629  int x2,
630  int y2,
631  Ogre::PixelBox& dst_box,
632  const std::string& material_scheme,
633  unsigned texture_width,
634  unsigned texture_height)
635 {
637 
638  if (x1 > x2)
639  std::swap(x1, x2);
640  if (y1 > y2)
641  std::swap(y1, y2);
642 
643  if (x1 < 0)
644  x1 = 0;
645  if (y1 < 0)
646  y1 = 0;
647  if (x1 > viewport->getActualWidth() - 2)
648  x1 = viewport->getActualWidth() - 2;
649  if (y1 > viewport->getActualHeight() - 2)
650  y1 = viewport->getActualHeight() - 2;
651  if (x2 < 0)
652  x2 = 0;
653  if (y2 < 0)
654  y2 = 0;
655  if (x2 > viewport->getActualWidth() - 2)
656  x2 = viewport->getActualWidth() - 2;
657  if (y2 > viewport->getActualHeight() - 2)
658  y2 = viewport->getActualHeight() - 2;
659 
660  if (x2 == x1)
661  x2++;
662  if (y2 == y1)
663  y2++;
664 
665  if (x2 == x1 || y2 == y1)
666  {
667  ROS_WARN("SelectionManager::render(): not rendering 0 size area.");
669  return false;
670  }
671 
672  unsigned w = x2 - x1;
673  unsigned h = y2 - y1;
674 
675  Ogre::HardwarePixelBufferSharedPtr pixel_buffer = tex->getBuffer();
676  Ogre::RenderTexture* render_texture = pixel_buffer->getRenderTarget();
677 
678  Ogre::Matrix4 proj_matrix = viewport->getCamera()->getProjectionMatrix();
679  Ogre::Matrix4 scale_matrix = Ogre::Matrix4::IDENTITY;
680  Ogre::Matrix4 trans_matrix = Ogre::Matrix4::IDENTITY;
681 
682  float x1_rel = static_cast<float>(x1) / static_cast<float>(viewport->getActualWidth() - 1) - 0.5f;
683  float y1_rel = static_cast<float>(y1) / static_cast<float>(viewport->getActualHeight() - 1) - 0.5f;
684  float x2_rel = static_cast<float>(x2) / static_cast<float>(viewport->getActualWidth() - 1) - 0.5f;
685  float y2_rel = static_cast<float>(y2) / static_cast<float>(viewport->getActualHeight() - 1) - 0.5f;
686 
687  scale_matrix[0][0] = 1.0 / (x2_rel - x1_rel);
688  scale_matrix[1][1] = 1.0 / (y2_rel - y1_rel);
689 
690  trans_matrix[0][3] -= x1_rel + x2_rel;
691  trans_matrix[1][3] += y1_rel + y2_rel;
692 
693  camera_->setCustomProjectionMatrix(true, scale_matrix * trans_matrix * proj_matrix);
694 
695  camera_->setPosition(viewport->getCamera()->getDerivedPosition());
696  camera_->setOrientation(viewport->getCamera()->getDerivedOrientation());
697 
698  // create a viewport if there is none
699  if (render_texture->getNumViewports() == 0)
700  {
701  render_texture->removeAllViewports();
702  render_texture->addViewport(camera_);
703  Ogre::Viewport* render_viewport = render_texture->getViewport(0);
704  render_viewport->setClearEveryFrame(true);
705  render_viewport->setBackgroundColour(Ogre::ColourValue::Black);
706  render_viewport->setOverlaysEnabled(false);
707  render_viewport->setMaterialScheme(material_scheme);
708  }
709 
710  unsigned render_w = w;
711  unsigned render_h = h;
712 
713  if (w > h)
714  {
715  if (render_w > texture_width)
716  {
717  render_w = texture_width;
718  render_h = round(float(h) * (float)texture_width / (float)w);
719  }
720  }
721  else
722  {
723  if (render_h > texture_height)
724  {
725  render_h = texture_height;
726  render_w = round(float(w) * (float)texture_height / (float)h);
727  }
728  }
729 
730  // safety clamping in case of rounding errors
731  if (render_w > texture_width)
732  render_w = texture_width;
733  if (render_h > texture_height)
734  render_h = texture_height;
735 
736  // set viewport to render to a subwindow of the texture
737  Ogre::Viewport* render_viewport = render_texture->getViewport(0);
738  render_viewport->setDimensions(0, 0, (float)render_w / (float)texture_width,
739  (float)render_h / (float)texture_height);
740 
741  // make sure the same objects are visible as in the original viewport
742  render_viewport->setVisibilityMask(viewport->getVisibilityMask());
743 
745 
746  // update & force ogre to render the scene
747  Ogre::MaterialManager::getSingleton().addListener(this);
748 
749  render_texture->update();
750 
751  // For some reason we need to pretend to render the main window in
752  // order to get the picking render to show up in the pixelbox below.
753  // If we don't do this, it will show up there the *next* time we
754  // pick something, but not this time. This object as a
755  // render queue listener tells the scene manager to skip every
756  // render step, so nothing actually gets drawn.
757  //
758  // TODO: find out what part of _renderScene() actually makes this work.
759  Ogre::Viewport* main_view = vis_manager_->getRenderPanel()->getViewport();
760  vis_manager_->getSceneManager()->addRenderQueueListener(this);
761  vis_manager_->getSceneManager()->_renderScene(main_view->getCamera(), main_view, false);
762  vis_manager_->getSceneManager()->removeRenderQueueListener(this);
763 
765  ros::WallDuration d = end - start;
766  // ROS_DEBUG("Render took [%f] msec", d.toSec() * 1000.0f);
767  Q_UNUSED(d);
768 
769  Ogre::MaterialManager::getSingleton().removeListener(this);
770 
771  render_w = render_viewport->getActualWidth();
772  render_h = render_viewport->getActualHeight();
773 
774  Ogre::PixelFormat format = pixel_buffer->getFormat();
775 
776  int size = Ogre::PixelUtil::getMemorySize(render_w, render_h, 1, format);
777  uint8_t* data = new uint8_t[size];
778 
779  delete[](uint8_t*) dst_box.data;
780  dst_box = Ogre::PixelBox(render_w, render_h, 1, format, data);
781 
782  pixel_buffer->blitToMemory(dst_box, dst_box);
783 
785 
786  if (debug_mode_)
787  {
788  publishDebugImage(dst_box, material_scheme);
789  }
790 
791  return true;
792 }
793 
794 void SelectionManager::publishDebugImage(const Ogre::PixelBox& pixel_box, const std::string& label)
795 {
796  ros::Publisher pub;
797  ros::NodeHandle nh;
798  PublisherMap::const_iterator iter = debug_publishers_.find(label);
799  if (iter == debug_publishers_.end())
800  {
801  pub = nh.advertise<sensor_msgs::Image>("/rviz_debug/" + label, 2);
802  debug_publishers_[label] = pub;
803  }
804  else
805  {
806  pub = iter->second;
807  }
808 
809  sensor_msgs::Image msg;
810  msg.header.stamp = ros::Time::now();
811  msg.width = pixel_box.getWidth();
812  msg.height = pixel_box.getHeight();
813  msg.encoding = sensor_msgs::image_encodings::RGB8;
814  msg.is_bigendian = false;
815  msg.step = msg.width * 3;
816  int dest_byte_count = msg.width * msg.height * 3;
817  msg.data.resize(dest_byte_count);
818  int dest_index = 0;
819  uint8_t* source_ptr = (uint8_t*)pixel_box.data;
820  int pre_pixel_padding = 0;
821  int post_pixel_padding = 0;
822  switch (pixel_box.format)
823  {
824  case Ogre::PF_R8G8B8:
825  break;
826  case Ogre::PF_A8R8G8B8:
827  case Ogre::PF_X8R8G8B8:
828  post_pixel_padding = 1;
829  break;
830  case Ogre::PF_R8G8B8A8:
831  pre_pixel_padding = 1;
832  break;
833  default:
834  ROS_ERROR("SelectionManager::publishDebugImage(): Incompatible pixel format [%d]", pixel_box.format);
835  return;
836  }
837  uint8_t r, g, b;
838  while (dest_index < dest_byte_count)
839  {
840  source_ptr += pre_pixel_padding;
841  b = *source_ptr++;
842  g = *source_ptr++;
843  r = *source_ptr++;
844  source_ptr += post_pixel_padding;
845  msg.data[dest_index++] = r;
846  msg.data[dest_index++] = g;
847  msg.data[dest_index++] = b;
848  }
849 
850  pub.publish(msg);
851 }
852 
853 void SelectionManager::renderQueueStarted(uint8_t /*queueGroupId*/,
854  const std::string& /*invocation*/,
855  bool& skipThisInvocation)
856 {
857  // This render queue listener function tells the scene manager to
858  // skip every render step, so nothing actually gets drawn.
859 
860  // ROS_DEBUG("SelectionManager renderQueueStarted(%d, '%s') returning skip = true.",
861  // (int)queueGroupId, invocation.c_str());
862  skipThisInvocation = true;
863 }
864 
865 void SelectionManager::pick(Ogre::Viewport* viewport,
866  int x1,
867  int y1,
868  int x2,
869  int y2,
870  M_Picked& results,
871  bool single_render_pass)
872 {
873  boost::recursive_mutex::scoped_lock lock(global_mutex_);
874 
875  bool need_additional_render = false;
876 
877  V_CollObject handles_by_pixel;
878  S_CollObject need_additional;
879 
880  V_CollObject& pixels = pixel_buffer_;
881 
882  // First render is special... does the initial object picking, determines which objects have been
883  // selected
884  // After that, individual handlers can specify that they need additional renders (max # defined in
885  // s_num_render_textures_)
886  {
887  M_CollisionObjectToSelectionHandler::iterator handler_it = objects_.begin();
888  M_CollisionObjectToSelectionHandler::iterator handler_end = objects_.end();
889  for (; handler_it != handler_end; ++handler_it)
890  {
891  handler_it->second->preRenderPass(0);
892  }
893 
894  renderAndUnpack(viewport, 0, x1, y1, x2, y2, pixels);
895 
896  handler_it = objects_.begin();
897  handler_end = objects_.end();
898  for (; handler_it != handler_end; ++handler_it)
899  {
900  handler_it->second->postRenderPass(0);
901  }
902 
903  handles_by_pixel.reserve(pixels.size());
904  V_CollObject::iterator it = pixels.begin();
905  V_CollObject::iterator end = pixels.end();
906  for (; it != end; ++it)
907  {
908  const CollObjectHandle& p = *it;
909 
910  CollObjectHandle handle = p;
911 
912  handles_by_pixel.push_back(handle);
913 
914  if (handle == 0)
915  {
916  continue;
917  }
918 
919  SelectionHandler* handler = getHandler(handle);
920 
921  if (handler)
922  {
923  std::pair<M_Picked::iterator, bool> insert_result =
924  results.insert(std::make_pair(handle, Picked(handle)));
925  if (insert_result.second)
926  {
927  if (handler->needsAdditionalRenderPass(1) && !single_render_pass)
928  {
929  need_additional.insert(handle);
930  need_additional_render = true;
931  }
932  }
933  else
934  {
935  insert_result.first->second.pixel_count++;
936  }
937  }
938  }
939  }
940 
941  uint32_t pass = 1;
942 
943  V_uint64 extra_by_pixel;
944  extra_by_pixel.resize(handles_by_pixel.size());
945  while (need_additional_render && pass < s_num_render_textures_)
946  {
947  {
948  S_CollObject::iterator need_it = need_additional.begin();
949  S_CollObject::iterator need_end = need_additional.end();
950  for (; need_it != need_end; ++need_it)
951  {
952  SelectionHandler* handler = getHandler(*need_it);
953  ROS_ASSERT(handler);
954 
955  handler->preRenderPass(pass);
956  }
957  }
958 
959  renderAndUnpack(viewport, pass, x1, y1, x2, y2, pixels);
960 
961  {
962  S_CollObject::iterator need_it = need_additional.begin();
963  S_CollObject::iterator need_end = need_additional.end();
964  for (; need_it != need_end; ++need_it)
965  {
966  SelectionHandler* handler = getHandler(*need_it);
967  ROS_ASSERT(handler);
968 
969  handler->postRenderPass(pass);
970  }
971  }
972 
973  int i = 0;
974  V_CollObject::iterator pix_it = pixels.begin();
975  V_CollObject::iterator pix_end = pixels.end();
976  for (; pix_it != pix_end; ++pix_it, ++i)
977  {
978  const CollObjectHandle& p = *pix_it;
979 
980  CollObjectHandle handle = handles_by_pixel[i];
981 
982  if (pass == 1)
983  {
984  extra_by_pixel[i] = 0;
985  }
986 
987  if (need_additional.find(handle) != need_additional.end())
988  {
989  CollObjectHandle extra_handle = p;
990  extra_by_pixel[i] |= extra_handle << (32 * (pass - 1));
991  }
992  else
993  {
994  extra_by_pixel[i] = 0;
995  }
996  }
997 
998  need_additional_render = false;
999  need_additional.clear();
1000  M_Picked::iterator handle_it = results.begin();
1001  M_Picked::iterator handle_end = results.end();
1002  for (; handle_it != handle_end; ++handle_it)
1003  {
1004  CollObjectHandle handle = handle_it->first;
1005 
1006  if (getHandler(handle)->needsAdditionalRenderPass(pass + 1))
1007  {
1008  need_additional_render = true;
1009  need_additional.insert(handle);
1010  }
1011  }
1012  }
1013 
1014  int i = 0;
1015  V_uint64::iterator pix_2_it = extra_by_pixel.begin();
1016  V_uint64::iterator pix_2_end = extra_by_pixel.end();
1017  for (; pix_2_it != pix_2_end; ++pix_2_it, ++i)
1018  {
1019  CollObjectHandle handle = handles_by_pixel[i];
1020 
1021  if (handle == 0)
1022  {
1023  continue;
1024  }
1025 
1026  M_Picked::iterator picked_it = results.find(handle);
1027  if (picked_it == results.end())
1028  {
1029  continue;
1030  }
1031 
1032  Picked& picked = picked_it->second;
1033 
1034  if (*pix_2_it)
1035  {
1036  picked.extra_handles.insert(*pix_2_it);
1037  }
1038  }
1039 }
1040 
1041 Ogre::Technique* SelectionManager::handleSchemeNotFound(unsigned short /*scheme_index*/,
1042  const Ogre::String& scheme_name,
1043  Ogre::Material* original_material,
1044  unsigned short /*lod_index*/,
1045  const Ogre::Renderable* rend)
1046 {
1047  // Find the original culling mode
1048  Ogre::CullingMode culling_mode = Ogre::CULL_CLOCKWISE;
1049  Ogre::Technique* orig_tech = original_material->getTechnique(0);
1050  if (orig_tech && orig_tech->getNumPasses() > 0)
1051  {
1052  culling_mode = orig_tech->getPass(0)->getCullingMode();
1053  }
1054 
1055  // find out if the renderable has the picking param set
1056  bool has_pick_param = !rend->getUserObjectBindings().getUserAny("pick_handle").isEmpty();
1057 
1058  // NOTE: it is important to avoid changing the culling mode of the
1059  // fallback techniques here, because that change then propagates to
1060  // other uses of these fallback techniques in unpredictable ways.
1061  // If you want to change the technique programmatically (like with
1062  // Pass::setCullingMode()), make sure you do it on a cloned material
1063  // which doesn't get shared with other objects.
1064 
1065  // Use the technique with the right name and culling mode.
1066  if (culling_mode == Ogre::CULL_CLOCKWISE)
1067  {
1068  if (scheme_name == "Pick")
1069  {
1071  }
1072  else if (scheme_name == "Depth")
1073  {
1075  }
1076  if (scheme_name == "Pick1")
1077  {
1079  }
1080  else
1081  {
1082  return nullptr;
1083  }
1084  }
1085  else // Must be CULL_NONE because we never use CULL_ANTICLOCKWISE
1086  {
1087  if (scheme_name == "Pick")
1088  {
1089  return has_pick_param ? fallback_pick_technique_ : fallback_black_technique_;
1090  }
1091  else if (scheme_name == "Depth")
1092  {
1094  }
1095  if (scheme_name == "Pick1")
1096  {
1098  }
1099  else
1100  {
1101  return nullptr;
1102  }
1103  }
1104 }
1105 
1107 {
1108  float r = ((handle >> 16) & 0xff) / 255.0f;
1109  float g = ((handle >> 8) & 0xff) / 255.0f;
1110  float b = (handle & 0xff) / 255.0f;
1111  return Ogre::ColourValue(r, g, b, 1.0f);
1112 }
1113 
1115  const Ogre::ColourValue& color,
1116  Ogre::SceneNode* node)
1117 {
1118  if (!node)
1119  {
1120  return;
1121  }
1122  // Loop over all objects attached to this node.
1123  Ogre::SceneNode::ObjectIterator obj_it = node->getAttachedObjectIterator();
1124  while (obj_it.hasMoreElements())
1125  {
1126  Ogre::MovableObject* obj = obj_it.getNext();
1127  setPickData(handle, color, obj);
1128  }
1129  // Loop over and recurse into all child nodes.
1130  Ogre::SceneNode::ChildNodeIterator child_it = node->getChildIterator();
1131  while (child_it.hasMoreElements())
1132  {
1133  Ogre::SceneNode* child = dynamic_cast<Ogre::SceneNode*>(child_it.getNext());
1134  setPickData(handle, color, child);
1135  }
1136 }
1137 
1138 class PickColorSetter : public Ogre::Renderable::Visitor
1139 {
1140 public:
1141  PickColorSetter(CollObjectHandle handle, const Ogre::ColourValue& color)
1142  : color_vector_(color.r, color.g, color.b, 1.0), handle_(handle)
1143  {
1144  }
1145 
1146  void visit(Ogre::Renderable* rend,
1147  ushort /*lodIndex*/,
1148  bool /*isDebug*/,
1149  Ogre::Any* /*pAny*/ = nullptr) override
1150  {
1151  rend->setCustomParameter(PICK_COLOR_PARAMETER, color_vector_);
1152  rend->getUserObjectBindings().setUserAny("pick_handle", Ogre::Any(handle_));
1153  }
1154 
1155  Ogre::Vector4 color_vector_;
1157 };
1158 
1160  const Ogre::ColourValue& color,
1161  Ogre::MovableObject* object)
1162 {
1163  PickColorSetter visitor(handle, color);
1164  object->visitRenderables(&visitor);
1165  object->getUserObjectBindings().setUserAny("pick_handle", Ogre::Any(handle));
1166 }
1167 
1169 {
1170  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1171 
1172  M_CollisionObjectToSelectionHandler::iterator it = objects_.find(obj);
1173  if (it != objects_.end())
1174  {
1175  return it->second;
1176  }
1177 
1178  return nullptr;
1179 }
1180 
1182 {
1183  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1184 
1185  M_Picked::const_iterator it = objs.begin();
1186  M_Picked::const_iterator end = objs.end();
1187  for (; it != end; ++it)
1188  {
1189  removeSelectedObject(it->second);
1190  }
1191 
1192  selectionRemoved(objs);
1193 }
1194 
1196 {
1197  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1198 
1199  M_Picked added;
1200  M_Picked::const_iterator it = objs.begin();
1201  M_Picked::const_iterator end = objs.end();
1202  for (; it != end; ++it)
1203  {
1204  std::pair<Picked, bool> ppb = addSelectedObject(it->second);
1205  if (ppb.second)
1206  {
1207  added.insert(std::make_pair(it->first, ppb.first));
1208  }
1209  }
1210 
1211  selectionAdded(added);
1212 }
1213 
1215 {
1216  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1217 
1218  M_Picked original(selection_.begin(), selection_.end());
1219 
1220  removeSelection(original);
1221  addSelection(objs);
1222 }
1223 
1224 std::pair<Picked, bool> SelectionManager::addSelectedObject(const Picked& obj)
1225 {
1226  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1227 
1228  std::pair<M_Picked::iterator, bool> pib = selection_.insert(std::make_pair(obj.handle, obj));
1229 
1230  SelectionHandler* handler = getHandler(obj.handle);
1231 
1232  if (pib.second)
1233  {
1234  handler->onSelect(obj);
1235  return std::make_pair(obj, true);
1236  }
1237  else
1238  {
1239  Picked& cur = pib.first->second;
1240  Picked added(cur.handle);
1241 
1242  S_uint64::iterator it = obj.extra_handles.begin();
1243  S_uint64::iterator end = obj.extra_handles.end();
1244  for (; it != end; ++it)
1245  {
1246  if (cur.extra_handles.insert(*it).second)
1247  {
1248  added.extra_handles.insert(*it);
1249  }
1250  }
1251 
1252  if (!added.extra_handles.empty())
1253  {
1254  handler->onSelect(added);
1255 
1256  return std::make_pair(added, true);
1257  }
1258  }
1259 
1260  return std::make_pair(Picked(0), false);
1261 }
1262 
1264 {
1265  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1266 
1267  M_Picked::iterator sel_it = selection_.find(obj.handle);
1268  if (sel_it != selection_.end())
1269  {
1270  S_uint64::iterator extra_it = obj.extra_handles.begin();
1271  S_uint64::iterator extra_end = obj.extra_handles.end();
1272  for (; extra_it != extra_end; ++extra_it)
1273  {
1274  sel_it->second.extra_handles.erase(*extra_it);
1275  }
1276 
1277  if (sel_it->second.extra_handles.empty())
1278  {
1279  selection_.erase(sel_it);
1280  }
1281  }
1282 
1283  SelectionHandler* handler = getHandler(obj.handle);
1284  handler->onDeselect(obj);
1285 }
1286 
1288 {
1289  boost::recursive_mutex::scoped_lock lock(global_mutex_);
1290 
1291  if (selection_.empty())
1292  {
1293  return;
1294  }
1295 
1296  Ogre::AxisAlignedBox combined;
1297 
1298  M_Picked::iterator it = selection_.begin();
1299  M_Picked::iterator end = selection_.end();
1300  for (; it != end; ++it)
1301  {
1302  const Picked& p = it->second;
1303 
1304  SelectionHandler* handler = getHandler(p.handle);
1305 
1306  V_AABB aabbs;
1307  handler->getAABBs(p, aabbs);
1308 
1309  V_AABB::iterator aabb_it = aabbs.begin();
1310  V_AABB::iterator aabb_end = aabbs.end();
1311  for (; aabb_it != aabb_end; ++aabb_it)
1312  {
1313  combined.merge(*aabb_it);
1314  }
1315  }
1316 
1317  if (!combined.isInfinite() && !combined.isNull())
1318  {
1319  Ogre::Vector3 center = combined.getCenter();
1321  if (controller)
1322  {
1323  controller->lookAt(center);
1324  }
1325  }
1326 }
1327 
1329 {
1330  M_Picked::const_iterator it = removed.begin();
1331  M_Picked::const_iterator end = removed.end();
1332  for (; it != end; ++it)
1333  {
1334  const Picked& picked = it->second;
1335  SelectionHandler* handler = getHandler(picked.handle);
1336  ROS_ASSERT(handler);
1337 
1338  handler->destroyProperties(picked, property_model_->getRoot());
1339  }
1340 }
1341 
1343 {
1344  M_Picked::const_iterator it = added.begin();
1345  M_Picked::const_iterator end = added.end();
1346  for (; it != end; ++it)
1347  {
1348  const Picked& picked = it->second;
1349  SelectionHandler* handler = getHandler(picked.handle);
1350  ROS_ASSERT(handler);
1351 
1352  handler->createProperties(picked, property_model_->getRoot());
1353  }
1354  property_model_->sort(0, Qt::AscendingOrder);
1355 }
1356 
1358 {
1359  M_Picked::const_iterator it = selection_.begin();
1360  M_Picked::const_iterator end = selection_.end();
1361  for (; it != end; ++it)
1362  {
1363  CollObjectHandle handle = it->first;
1364  SelectionHandler* handler = getHandler(handle);
1365 
1366  handler->updateProperties();
1367  }
1368 }
1369 
1370 
1371 } // namespace rviz
rviz::SelectionManager::highlight_enabled_
bool highlight_enabled_
Definition: selection_manager.h:291
rviz::SelectionManager::vis_manager_
VisualizationManager * vis_manager_
Definition: selection_manager.h:284
shape.h
axes.h
PICK_COLOR_PARAMETER
#define PICK_COLOR_PARAMETER
Definition: custom_parameter_indices.h:43
rviz::SelectionManager::enableInteraction
void enableInteraction(bool enable)
Definition: selection_manager.cpp:423
node_handle.h
view_manager.h
rviz::SelectionManager::depth_pixel_box_
Ogre::PixelBox depth_pixel_box_
Definition: selection_manager.h:314
ros::Publisher
rviz::SelectionManager::global_mutex_
boost::recursive_mutex global_mutex_
Definition: selection_manager.h:286
image_encodings.h
compatibility.h
rviz::SelectionManager::uid_counter_
uint32_t uid_counter_
Definition: selection_manager.h:316
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr
rviz::SelectionManager::select
void select(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, SelectType type)
Definition: selection_manager.cpp:540
rviz::SelectionManager::texture_size_
uint32_t texture_size_
Definition: selection_manager.h:336
rviz::SelectionManager::getHandler
SelectionHandler * getHandler(CollObjectHandle obj)
Definition: selection_manager.cpp:1168
rviz::SelectionManager::Replace
@ Replace
Definition: selection_manager.h:91
rviz::SelectionManager::initialize
void initialize()
Definition: selection_manager.cpp:122
rviz::Picked::handle
CollObjectHandle handle
Definition: forwards.h:59
rviz::SelectionManager::pick
void pick(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2, M_Picked &results, bool single_render_pass=false)
Definition: selection_manager.cpp:865
rviz::VisualizationManager
The VisualizationManager class is the central manager class of rviz, holding all the Displays,...
Definition: visualization_manager.h:96
rviz::PropertyTreeModel
Definition: property_tree_model.h:38
rviz::SelectionManager::Highlight::viewport
Ogre::Viewport * viewport
Definition: selection_manager.h:299
rviz::SelectionManager::addSelection
void addSelection(const M_Picked &objs)
Definition: selection_manager.cpp:1195
property.h
custom_parameter_indices.h
rviz::SelectionManager::clearHandlers
void clearHandlers()
Definition: selection_manager.cpp:416
rviz::SelectionManager::Highlight::x1
int x1
Definition: selection_manager.h:295
rviz::SelectionHandler::getAABBs
virtual void getAABBs(const Picked &obj, V_AABB &aabbs)
Definition: selection_handler.cpp:162
rviz::SelectionManager::fallback_black_cull_technique_
Ogre::Technique * fallback_black_cull_technique_
Definition: selection_manager.h:333
rviz::SelectionHandler::preRenderPass
virtual void preRenderPass(uint32_t pass)
Definition: selection_handler.cpp:75
rviz::V_uint64
std::vector< uint64_t > V_uint64
Definition: forwards.h:51
rviz::SelectionManager::s_num_render_textures_
const static uint32_t s_num_render_textures_
Definition: selection_manager.h:305
rviz::SelectionManager::removeHighlight
void removeHighlight()
Definition: selection_manager.cpp:533
rviz::V_CollObject
std::vector< CollObjectHandle > V_CollObject
Definition: forwards.h:46
rviz::Picked::extra_handles
S_uint64 extra_handles
Definition: forwards.h:61
rviz::SelectionManager::SelectType
SelectType
Definition: selection_manager.h:87
rviz::SelectionManager::renderAndUnpack
void renderAndUnpack(Ogre::Viewport *viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_CollObject &pixels)
Definition: selection_manager.cpp:600
rviz::SelectionManager::SelectionManager
SelectionManager(VisualizationManager *manager)
Definition: selection_manager.cpp:78
selection_manager.h
rviz::PickColorSetter
Definition: selection_manager.cpp:1138
rviz::SelectionManager::unpackColors
void unpackColors(Ogre::PixelBox &box, V_CollObject &pixels)
Definition: selection_manager.cpp:579
rviz::SelectionManager::Highlight::x2
int x2
Definition: selection_manager.h:297
rviz::SelectionManager::depth_texture_width_
uint32_t depth_texture_width_
Definition: selection_manager.h:313
rviz::S_CollObject
std::set< CollObjectHandle > S_CollObject
Definition: forwards.h:48
sensor_msgs::image_encodings::RGB8
const std::string RGB8
rviz::setMaterial
void setMaterial(Ogre::SimpleRenderable &renderable, const std::string &material_name)
Definition: compatibility.h:69
get
def get(url)
rviz::SelectionManager::handleSchemeNotFound
Ogre::Technique * handleSchemeNotFound(unsigned short scheme_index, const Ogre::String &scheme_name, Ogre::Material *original_material, unsigned short lod_index, const Ogre::Renderable *rend) override
Definition: selection_manager.cpp:1041
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rviz::CollObjectHandle
uint32_t CollObjectHandle
Definition: forwards.h:45
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
publisher.h
f
f
rviz::SelectionManager::fallback_black_technique_
Ogre::Technique * fallback_black_technique_
Definition: selection_manager.h:330
rviz::SelectionManager::fallback_pick_material_
Ogre::MaterialPtr fallback_pick_material_
Definition: selection_manager.h:328
rviz::SelectionManager::get3DPoint
bool get3DPoint(Ogre::Viewport *viewport, const int x, const int y, Ogre::Vector3 &result_point)
Definition: selection_manager.cpp:179
rviz::Picked
Definition: forwards.h:53
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz::SelectionManager::selectionRemoved
void selectionRemoved(const M_Picked &removed)
Definition: selection_manager.cpp:1328
rviz::SelectionManager::objects_
M_CollisionObjectToSelectionHandler objects_
Definition: selection_manager.h:289
rviz::SelectionManager::Highlight::y2
int y2
Definition: selection_manager.h:298
rviz::removeAndDestroyChildNode
void removeAndDestroyChildNode(Ogre::SceneNode *parent, Ogre::SceneNode *child)
Definition: compatibility.h:96
rviz::SelectionManager::addObject
void addObject(CollObjectHandle obj, SelectionHandler *handler)
Definition: selection_manager.cpp:459
rviz::SelectionManager::highlight_rectangle_
Ogre::Rectangle2D * highlight_rectangle_
Definition: selection_manager.h:318
rviz::PickColorSetter::handle_
CollObjectHandle handle_
Definition: selection_manager.cpp:1156
rviz::SelectionManager::pixel_buffer_
V_CollObject pixel_buffer_
Definition: selection_manager.h:322
rviz::VisualizationManager::getViewManager
ViewManager * getViewManager() const override
Return a pointer to the ViewManager.
Definition: visualization_manager.h:270
rviz::SelectionManager::interaction_enabled_
bool interaction_enabled_
Definition: selection_manager.h:324
ROS_DEBUG
#define ROS_DEBUG(...)
rviz
Definition: add_display_dialog.cpp:54
rviz::SelectionManager::debug_publishers_
PublisherMap debug_publishers_
Definition: selection_manager.h:341
ros::WallTime::now
static WallTime now()
rviz::SelectionManager::removeSelectedObject
void removeSelectedObject(const Picked &obj)
Definition: selection_manager.cpp:1263
rviz::SelectionManager::update
void update()
Definition: selection_manager.cpp:501
rviz::SelectionHandler::createProperties
virtual void createProperties(const Picked &, Property *)
Override to create properties of the given picked object(s).
Definition: selection_handler.h:83
rviz::SelectionManager::addSelectedObject
std::pair< Picked, bool > addSelectedObject(const Picked &obj)
Definition: selection_manager.cpp:1224
arrow.h
rviz::SelectionHandler::updateProperties
virtual void updateProperties()
Override to update property values.
Definition: selection_handler.h:105
rviz::SelectionManager::~SelectionManager
~SelectionManager() override
Definition: selection_manager.cpp:97
d
d
rviz::SelectionManager::getPatchDepthImage
bool getPatchDepthImage(Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, std::vector< float > &depth_vector)
Renders a depth image in a box around a point in a view port.
Definition: selection_manager.cpp:196
ROS_WARN
#define ROS_WARN(...)
rviz::ViewManager::getCurrent
ViewController * getCurrent() const
Return the current ViewController in use for the main RenderWindow.
Definition: view_manager.cpp:90
rviz::PropertyTreeModel::getRoot
Property * getRoot() const
Definition: property_tree_model.h:114
property_tree_model.h
rviz::SelectionManager::setDebugMode
void setDebugMode(bool debug)
Enables or disables publishing of picking and depth rendering images.
Definition: selection_manager.cpp:117
rviz::SelectionManager::pixel_boxes_
Ogre::PixelBox pixel_boxes_[s_num_render_textures_]
Definition: selection_manager.h:309
rviz::SelectionManager::get3DPatch
bool get3DPatch(Ogre::Viewport *viewport, const int x, const int y, const unsigned width, const unsigned height, const bool skip_missing, std::vector< Ogre::Vector3 > &result_points)
Gets the 3D points in a box around a point in a view port.
Definition: selection_manager.cpp:250
ros::WallTime
rviz::SelectionHandler::needsAdditionalRenderPass
virtual bool needsAdditionalRenderPass(uint32_t)
Definition: selection_handler.h:109
rviz::SelectionManager::focusOnSelection
void focusOnSelection()
Definition: selection_manager.cpp:1287
rviz::PickColorSetter::visit
void visit(Ogre::Renderable *rend, ushort, bool, Ogre::Any *=nullptr) override
Definition: selection_manager.cpp:1146
rviz::PickColorSetter::color_vector_
Ogre::Vector4 color_vector_
Definition: selection_manager.cpp:1155
rviz::SelectionManager::removeObject
void removeObject(CollObjectHandle obj)
Definition: selection_manager.cpp:480
visualization_manager.h
render_panel.h
rviz::SelectionManager::depth_texture_height_
uint32_t depth_texture_height_
Definition: selection_manager.h:313
rviz::SelectionManager::fallback_depth_cull_technique_
Ogre::Technique * fallback_depth_cull_technique_
Definition: selection_manager.h:334
rviz::SelectionManager::removeSelection
void removeSelection(const M_Picked &objs)
Definition: selection_manager.cpp:1181
start
ROSCPP_DECL void start()
rviz::SelectionManager::selectionAdded
void selectionAdded(const M_Picked &added)
Definition: selection_manager.cpp:1342
rviz::V_AABB
std::vector< Ogre::AxisAlignedBox > V_AABB
Definition: selection_handler.h:60
rviz::SelectionManager::Highlight::y1
int y1
Definition: selection_manager.h:296
rviz::SelectionManager::setHighlightRect
void setHighlightRect(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
Definition: selection_manager.cpp:564
rviz::VisualizationManager::unlockRender
void unlockRender()
Unlock a mutex, allowing calls to Ogre::Root::renderOneFrame().
Definition: visualization_manager.cpp:268
rviz::SelectionManager::fallback_pick_technique_
Ogre::Technique * fallback_pick_technique_
Definition: selection_manager.h:329
rviz::PickColorSetter::PickColorSetter
PickColorSetter(CollObjectHandle handle, const Ogre::ColourValue &color)
Definition: selection_manager.cpp:1141
rviz::ViewController
Definition: view_controller.h:55
rviz::SelectionHandler::onDeselect
virtual void onDeselect(const Picked &obj)
Definition: selection_handler.cpp:249
rviz::SelectionHandler
Definition: selection_handler.h:64
rviz::SelectionManager::Remove
@ Remove
Definition: selection_manager.h:90
rviz::SelectionManager::handleToColor
static Ogre::ColourValue handleToColor(CollObjectHandle handle)
Definition: selection_manager.cpp:1106
rviz::SelectionHandler::onSelect
virtual void onSelect(const Picked &obj)
Definition: selection_handler.cpp:228
rviz::VisualizationManager::lockRender
void lockRender()
Lock a mutex to delay calls to Ogre::Root::renderOneFrame().
Definition: visualization_manager.cpp:263
rviz::SelectionManager::debug_mode_
bool debug_mode_
Definition: selection_manager.h:326
ROS_ERROR
#define ROS_ERROR(...)
rviz::SelectionManager::setSelection
void setSelection(const M_Picked &objs)
Definition: selection_manager.cpp:1214
rviz::SelectionManager::selection_
M_Picked selection_
Definition: selection_manager.h:303
rviz::SelectionManager::highlight
void highlight(Ogre::Viewport *viewport, int x1, int y1, int x2, int y2)
Definition: selection_manager.cpp:520
rviz::SelectionManager::Add
@ Add
Definition: selection_manager.h:89
rviz::SelectionManager::setDepthTextureSize
void setDepthTextureSize(unsigned width, unsigned height)
Definition: selection_manager.cpp:327
view_controller.h
rviz::SelectionManager::render_textures_
Ogre::TexturePtr render_textures_[s_num_render_textures_]
Definition: selection_manager.h:308
rviz::SelectionHandler::getInteractiveObject
virtual InteractiveObjectWPtr getInteractiveObject()
Get the object to listen to mouse events and other interaction calls during use of the 'interact' too...
Definition: selection_handler.cpp:261
rviz::SelectionHandler::destroyProperties
virtual void destroyProperties(const Picked &obj, Property *parent_property)
Destroy all properties for the given picked object(s).
Definition: selection_handler.cpp:172
rviz::SelectionManager::fallback_pick_cull_technique_
Ogre::Technique * fallback_pick_cull_technique_
Definition: selection_manager.h:332
ros::WallDuration
rviz::SelectionManager::publishDebugImage
void publishDebugImage(const Ogre::PixelBox &pixel_box, const std::string &label)
Definition: selection_manager.cpp:794
rviz::VisualizationManager::getSceneManager
Ogre::SceneManager * getSceneManager() const override
Returns the Ogre::SceneManager used for the main RenderPanel.
Definition: visualization_manager.h:199
rviz::ViewController::lookAt
void lookAt(float x, float y, float z)
Convenience function which calls lookAt(Ogre::Vector3).
Definition: view_controller.cpp:229
rviz::SelectionManager::highlight_node_
Ogre::SceneNode * highlight_node_
Definition: selection_manager.h:319
rviz::SelectionManager::depth_render_texture_
Ogre::TexturePtr depth_render_texture_
Definition: selection_manager.h:312
rviz::SelectionHandler::postRenderPass
virtual void postRenderPass(uint32_t pass)
Definition: selection_handler.cpp:86
assert.h
rviz::SelectionManager::updateProperties
void updateProperties()
Call updateProperties() on all SelectionHandlers in the current selection.
Definition: selection_manager.cpp:1357
rviz::SelectionManager::setTextureSize
void setTextureSize(unsigned size)
Definition: selection_manager.cpp:375
rviz::SelectionManager::createHandle
CollObjectHandle createHandle()
Definition: selection_manager.cpp:437
ROS_ASSERT
#define ROS_ASSERT(cond)
rviz::QtOgreRenderWindow::getViewport
Ogre::Viewport * getViewport() const
Definition: qt_ogre_render_window.cpp:214
rviz::SelectionManager::setPickData
static void setPickData(CollObjectHandle handle, const Ogre::ColourValue &color, Ogre::SceneNode *node)
Definition: selection_manager.cpp:1114
rviz::SelectionManager::highlight_
Highlight highlight_
Definition: selection_manager.h:301
rviz::VisualizationManager::getRenderPanel
RenderPanel * getRenderPanel() const
Return the main RenderPanel.
Definition: visualization_manager.h:207
rviz::M_Picked
boost::unordered_map< CollObjectHandle, Picked > M_Picked
Definition: forwards.h:63
rviz::SelectionManager::fallback_depth_technique_
Ogre::Technique * fallback_depth_technique_
Definition: selection_manager.h:331
rviz::colorToHandle
uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
Definition: forwards.h:66
rviz::SelectionManager::renderQueueStarted
void renderQueueStarted(uint8_t queueGroupId, const std::string &invocation, bool &skipThisInvocation) override
Definition: selection_manager.cpp:853
qt_ogre_render_window.h
ros::NodeHandle
rviz::SelectionManager::property_model_
PropertyTreeModel * property_model_
Definition: selection_manager.h:338
rviz::SelectionManager::render
bool render(Ogre::Viewport *viewport, const Ogre::TexturePtr &tex, int x1, int y1, int x2, int y2, Ogre::PixelBox &dst_box, const std::string &material_scheme, unsigned texture_width, unsigned textured_height)
Definition: selection_manager.cpp:625
ros::Time::now
static Time now()
rviz::SelectionManager::camera_
Ogre::Camera * camera_
Definition: selection_manager.h:320


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Thu May 16 2024 02:30:49