selection_manager.h
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 #ifndef RVIZ_SELECTION_MANAGER_H
31 #define RVIZ_SELECTION_MANAGER_H
32 
33 #include <map>
34 
35 #include <QObject>
36 
37 #include "forwards.h"
38 #include "selection_handler.h"
39 
40 #ifndef Q_MOC_RUN
41 #include <boost/shared_ptr.hpp>
42 #include <boost/unordered_map.hpp>
43 #include <boost/thread/recursive_mutex.hpp>
44 
45 #include <OgreTexture.h>
46 #include <OgreMaterial.h>
47 #include <OgreMaterialManager.h>
48 #include <OgreMovableObject.h>
49 #include <OgreRenderQueueListener.h>
50 #include <OgreSharedPtr.h>
51 #endif
52 
53 #include <vector>
54 #include <set>
55 
56 namespace ros
57 {
58 class Publisher;
59 }
60 
61 namespace Ogre
62 {
63 class SceneManager;
64 class Viewport;
65 class WireBoundingBox;
66 class SceneNode;
67 class Material;
68 class PixelBox;
69 class Rectangle2D;
70 class MovableObject;
71 }
72 
73 namespace rviz
74 {
75 class Object;
76 class PropertyTreeModel;
77 class ViewportMouseEvent;
78 class VisualizationManager;
79 
80 class SelectionManager: public QObject, public Ogre::MaterialManager::Listener, public Ogre::RenderQueueListener
81 {
82 Q_OBJECT
83 public:
85  {
86  Add,
88  Replace
89  };
90 
93 
94  void initialize();
95 
97  void setDebugMode( bool debug );
98 
99  void clearHandlers();
100  void addObject( CollObjectHandle obj, SelectionHandler* handler );
101  void removeObject(CollObjectHandle obj);
102 
103  // control the highlight box being displayed while selecting
104  void highlight(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
105  void removeHighlight();
106 
107  // select all objects in bounding box
108  void select(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, SelectType type);
109 
110  // @return handles of all objects in the given bounding box
111  // @param single_render_pass only perform one rendering pass (point cloud selecting won't work)
112  void pick(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, M_Picked& results, bool single_render_pass=false );
113 
114  void update();
115 
116  // modify the list of currently selected objects
117  void setSelection(const M_Picked& objs);
118  void addSelection(const M_Picked& objs);
119  void removeSelection(const M_Picked& objs);
120  const M_Picked& getSelection() { return selection_; }
121 
122  SelectionHandler* getHandler( CollObjectHandle obj );
123 
124  static Ogre::ColourValue handleToColor( CollObjectHandle handle );
125  //static CollObjectHandle colourToHandle( const Ogre::ColourValue & color );
126  static void setPickColor( const Ogre::ColourValue& color, Ogre::SceneNode* node ) { setPickData( colorToHandle( color ), color, node ); }
127  static void setPickColor( const Ogre::ColourValue& color, Ogre::MovableObject* object ) { setPickData( colorToHandle( color ), color, object ); }
128  static void setPickHandle( CollObjectHandle handle, Ogre::SceneNode* node ) { setPickData( handle, handleToColor( handle ), node ); }
129  static void setPickHandle( CollObjectHandle handle, Ogre::MovableObject* object ) { setPickData( handle, handleToColor( handle ), object ); }
130  static void setPickData( CollObjectHandle handle, const Ogre::ColourValue& color, Ogre::SceneNode* node );
131  static void setPickData( CollObjectHandle handle, const Ogre::ColourValue& color, Ogre::MovableObject* object );
132 
133  // if a material does not support the picking scheme, paint it black
134  virtual Ogre::Technique* handleSchemeNotFound(unsigned short scheme_index,
135  const Ogre::String& scheme_name,
136  Ogre::Material* original_material,
137  unsigned short lod_index,
138  const Ogre::Renderable* rend);
139 
140  // create a new unique handle
141  CollObjectHandle createHandle();
142 
143  // tell all handlers that interactive mode is active/inactive
144  void enableInteraction( bool enable );
145  bool getInteractionEnabled() { return interaction_enabled_; }
146 
147  // tell the view controller to look at the selection
148  void focusOnSelection();
149 
150  // change the size of the off-screen selection buffer texture
151  void setTextureSize( unsigned size );
152 
156  bool get3DPoint( Ogre::Viewport* viewport, const int x, const int y, Ogre::Vector3& result_point );
157 
174  bool get3DPatch( Ogre::Viewport* viewport, const int x, const int y, const unsigned width,
175  const unsigned height, const bool skip_missing,
176  std::vector<Ogre::Vector3> &result_points );
177 
178 
194  bool getPatchDepthImage( Ogre::Viewport* viewport, const int x, const int y, const unsigned width,
195  const unsigned height, std::vector<float> & depth_vector);
196 
197  // Implementation for Ogre::RenderQueueListener.
198  void renderQueueStarted( uint8_t queueGroupId,
199  const std::string& invocation,
200  bool& skipThisInvocation );
201 
202  PropertyTreeModel* getPropertyModel() { return property_model_; }
203 
204 private Q_SLOTS:
207  void updateProperties();
208 
209 private:
210  void selectionAdded( const M_Picked& added );
211  void selectionRemoved( const M_Picked& removed );
212 
213  std::pair<Picked, bool> addSelectedObject(const Picked& obj);
214  void removeSelectedObject(const Picked& obj);
215 
216  void setHighlightRect(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
217 
219  void renderAndUnpack(Ogre::Viewport* viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_CollObject& pixels);
220 
222  bool render( Ogre::Viewport* viewport, Ogre::TexturePtr tex,
223  int x1, int y1, int x2, int y2,
224  Ogre::PixelBox& dst_box, std::string material_scheme,
225  unsigned texture_width, unsigned textured_height );
226 
227  void unpackColors(const Ogre::PixelBox& box, V_CollObject& pixels);
228 
229  void setDepthTextureSize(unsigned width, unsigned height);
230 
231  void publishDebugImage( const Ogre::PixelBox& pixel_box, const std::string& label );
232 
234 
235  boost::recursive_mutex global_mutex_;
236 
237  typedef boost::unordered_map<CollObjectHandle, SelectionHandler*> M_CollisionObjectToSelectionHandler;
238  M_CollisionObjectToSelectionHandler objects_;
239 
241 
242  struct Highlight
243  {
244  int x1;
245  int y1;
246  int x2;
247  int y2;
248  Ogre::Viewport* viewport;
249  };
251 
253 
254  const static uint32_t s_num_render_textures_ = 2; // If you want to change this number to something > 3 you must provide more width for extra handles in the Picked structure (currently a u64)
255  Ogre::TexturePtr render_textures_[s_num_render_textures_];
256  Ogre::PixelBox pixel_boxes_[s_num_render_textures_];
257 
258  // Graphics card -based depth finding of clicked points.
259  Ogre::TexturePtr depth_render_texture_;
260  uint32_t depth_texture_width_, depth_texture_height_;
261  Ogre::PixelBox depth_pixel_box_;
262 
263  uint32_t uid_counter_;
264 
265  Ogre::Rectangle2D* highlight_rectangle_;
266  Ogre::SceneNode* highlight_node_;
267  Ogre::Camera *camera_;
268 
270 
272 
274 
275  Ogre::MaterialPtr fallback_pick_material_;
276  Ogre::Technique *fallback_pick_technique_;
277  Ogre::Technique *fallback_black_technique_;
278  Ogre::Technique *fallback_depth_technique_;
282 
283  uint32_t texture_size_;
284 
286 
287  typedef std::map<std::string, ros::Publisher> PublisherMap;
288  PublisherMap debug_publishers_;
289 };
290 
291 } // namespace rviz
292 
293 #endif // RVIZ_SELECTION_MANAGER_H
ROSCONSOLE_DECL void initialize()
boost::unordered_map< CollObjectHandle, Picked > M_Picked
Definition: forwards.h:65
TFSIMD_FORCE_INLINE const tfScalar & y() const
Ogre::Technique * fallback_black_cull_technique_
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
Ogre::Technique * fallback_pick_cull_technique_
static void setPickHandle(CollObjectHandle handle, Ogre::SceneNode *node)
PropertyTreeModel * property_model_
Ogre::Technique * fallback_pick_technique_
std::map< std::string, ros::Publisher > PublisherMap
const M_Picked & getSelection()
Ogre::Technique * fallback_depth_cull_technique_
The VisualizationManager class is the central manager class of rviz, holding all the Displays...
static void setPickColor(const Ogre::ColourValue &color, Ogre::MovableObject *object)
std::vector< CollObjectHandle > V_CollObject
Definition: forwards.h:47
TFSIMD_FORCE_INLINE const tfScalar & x() const
boost::unordered_map< CollObjectHandle, SelectionHandler * > M_CollisionObjectToSelectionHandler
Ogre::TexturePtr depth_render_texture_
static void setPickHandle(CollObjectHandle handle, Ogre::MovableObject *object)
Ogre::Technique * fallback_depth_technique_
uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
Definition: forwards.h:68
Ogre::SceneNode * highlight_node_
VisualizationManager * vis_manager_
static void setPickColor(const Ogre::ColourValue &color, Ogre::SceneNode *node)
Ogre::Rectangle2D * highlight_rectangle_
Ogre::MaterialPtr fallback_pick_material_
Ogre::Technique * fallback_black_technique_
PropertyTreeModel * getPropertyModel()
Ogre::PixelBox depth_pixel_box_
boost::recursive_mutex global_mutex_
M_CollisionObjectToSelectionHandler objects_
uint32_t CollObjectHandle
Definition: forwards.h:46


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