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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51