selection_manager.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #ifndef RVIZ_SELECTION_MANAGER_H
00031 #define RVIZ_SELECTION_MANAGER_H
00032 
00033 #include <map>
00034 
00035 #include <QObject>
00036 
00037 #include "forwards.h"
00038 #include "selection_handler.h"
00039 
00040 #ifndef Q_MOC_RUN
00041 #include <boost/shared_ptr.hpp>
00042 #include <boost/unordered_map.hpp>
00043 #include <boost/thread/recursive_mutex.hpp>
00044 
00045 #include <OgreTexture.h>
00046 #include <OgreMaterial.h>
00047 #include <OgreMaterialManager.h>
00048 #include <OgreMovableObject.h>
00049 #include <OgreRenderQueueListener.h>
00050 #include <OgreSharedPtr.h>
00051 #endif
00052 
00053 #include <vector>
00054 #include <set>
00055 
00056 namespace ros
00057 {
00058 class Publisher;
00059 }
00060 
00061 namespace Ogre
00062 {
00063 class SceneManager;
00064 class Viewport;
00065 class WireBoundingBox;
00066 class SceneNode;
00067 class Material;
00068 class PixelBox;
00069 class Rectangle2D;
00070 class MovableObject;
00071 }
00072 
00073 namespace rviz
00074 {
00075 class Object;
00076 class PropertyTreeModel;
00077 class ViewportMouseEvent;
00078 class VisualizationManager;
00079 
00080 class SelectionManager: public QObject, public Ogre::MaterialManager::Listener, public Ogre::RenderQueueListener
00081 {
00082 Q_OBJECT
00083 public:
00084   enum SelectType
00085   {
00086     Add,
00087     Remove,
00088     Replace
00089   };
00090 
00091   SelectionManager(VisualizationManager* manager);
00092   ~SelectionManager();
00093 
00094   void initialize();
00095 
00097   void setDebugMode( bool debug );
00098 
00099   void clearHandlers();
00100   void addObject( CollObjectHandle obj, SelectionHandler* handler );
00101   void removeObject(CollObjectHandle obj);
00102 
00103   // control the highlight box being displayed while selecting
00104   void highlight(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
00105   void removeHighlight();
00106 
00107   // select all objects in bounding box
00108   void select(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, SelectType type);
00109 
00110   // @return handles of all objects in the given bounding box
00111   // @param single_render_pass only perform one rendering pass (point cloud selecting won't work)
00112   void pick(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, M_Picked& results, bool single_render_pass=false );
00113 
00114   void update();
00115 
00116   // modify the list of currently selected objects
00117   void setSelection(const M_Picked& objs);
00118   void addSelection(const M_Picked& objs);
00119   void removeSelection(const M_Picked& objs);
00120   const M_Picked& getSelection() { return selection_; }
00121 
00122   SelectionHandler* getHandler( CollObjectHandle obj );
00123 
00124   static Ogre::ColourValue handleToColor( CollObjectHandle handle );
00125   //static CollObjectHandle colourToHandle( const Ogre::ColourValue & color );
00126   static void setPickColor( const Ogre::ColourValue& color, Ogre::SceneNode* node )       { setPickData( colorToHandle( color ), color, node ); }
00127   static void setPickColor( const Ogre::ColourValue& color, Ogre::MovableObject* object ) { setPickData( colorToHandle( color ), color, object ); }
00128   static void setPickHandle( CollObjectHandle handle, Ogre::SceneNode* node )             { setPickData( handle, handleToColor( handle ), node ); }
00129   static void setPickHandle( CollObjectHandle handle, Ogre::MovableObject* object )       { setPickData( handle, handleToColor( handle ), object ); }
00130   static void setPickData( CollObjectHandle handle, const Ogre::ColourValue& color, Ogre::SceneNode* node );
00131   static void setPickData( CollObjectHandle handle, const Ogre::ColourValue& color, Ogre::MovableObject* object );
00132 
00133   // if a material does not support the picking scheme, paint it black
00134   virtual Ogre::Technique* handleSchemeNotFound(unsigned short scheme_index,
00135       const Ogre::String& scheme_name,
00136       Ogre::Material* original_material,
00137       unsigned short lod_index,
00138       const Ogre::Renderable* rend);
00139 
00140   // create a new unique handle
00141   CollObjectHandle createHandle();
00142 
00143   // tell all handlers that interactive mode is active/inactive
00144   void enableInteraction( bool enable );
00145   bool getInteractionEnabled() { return interaction_enabled_; }
00146 
00147   // tell the view controller to look at the selection
00148   void focusOnSelection();
00149 
00150   // change the size of the off-screen selection buffer texture
00151   void setTextureSize( unsigned size );
00152 
00156   bool get3DPoint( Ogre::Viewport* viewport, const int x, const int y, Ogre::Vector3& result_point );
00157 
00174   bool get3DPatch( Ogre::Viewport* viewport, const int x, const int y, const unsigned width, 
00175                    const unsigned height, const bool skip_missing, 
00176                    std::vector<Ogre::Vector3> &result_points );
00177 
00178 
00194   bool getPatchDepthImage( Ogre::Viewport* viewport, const int x, const int y,  const unsigned width, 
00195                            const unsigned height, std::vector<float> & depth_vector);
00196 
00197   // Implementation for Ogre::RenderQueueListener.
00198   void renderQueueStarted( uint8_t queueGroupId,
00199                            const std::string& invocation, 
00200                            bool& skipThisInvocation );
00201 
00202   PropertyTreeModel* getPropertyModel() { return property_model_; }
00203 
00204 private Q_SLOTS:
00207   void updateProperties();
00208 
00209 private:
00210   void selectionAdded( const M_Picked& added );
00211   void selectionRemoved( const M_Picked& removed );
00212 
00213   std::pair<Picked, bool> addSelectedObject(const Picked& obj);
00214   void removeSelectedObject(const Picked& obj);
00215 
00216   void setHighlightRect(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
00217 
00219   void renderAndUnpack(Ogre::Viewport* viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_CollObject& pixels);
00220 
00222   bool render( Ogre::Viewport* viewport, Ogre::TexturePtr tex,
00223                int x1, int y1, int x2, int y2,
00224                Ogre::PixelBox& dst_box, std::string material_scheme,
00225                unsigned texture_width, unsigned textured_height );
00226 
00227   void unpackColors(const Ogre::PixelBox& box, V_CollObject& pixels);
00228 
00229   void setDepthTextureSize(unsigned width, unsigned height);
00230 
00231   void publishDebugImage( const Ogre::PixelBox& pixel_box, const std::string& label );
00232 
00233   VisualizationManager* vis_manager_;
00234 
00235   boost::recursive_mutex global_mutex_;
00236 
00237   typedef boost::unordered_map<CollObjectHandle, SelectionHandler*> M_CollisionObjectToSelectionHandler;
00238   M_CollisionObjectToSelectionHandler objects_;
00239 
00240   bool highlight_enabled_;
00241 
00242   struct Highlight
00243   {
00244     int x1;
00245     int y1;
00246     int x2;
00247     int y2;
00248     Ogre::Viewport* viewport;
00249   };
00250   Highlight highlight_;
00251 
00252   M_Picked selection_;
00253 
00254   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)
00255   Ogre::TexturePtr render_textures_[s_num_render_textures_];
00256   Ogre::PixelBox pixel_boxes_[s_num_render_textures_];
00257 
00258   // Graphics card -based depth finding of clicked points.
00259   Ogre::TexturePtr depth_render_texture_;
00260   uint32_t depth_texture_width_, depth_texture_height_;
00261   Ogre::PixelBox depth_pixel_box_;
00262 
00263   uint32_t uid_counter_;
00264 
00265   Ogre::Rectangle2D* highlight_rectangle_;
00266   Ogre::SceneNode* highlight_node_;
00267   Ogre::Camera *camera_;
00268 
00269   V_CollObject pixel_buffer_;
00270 
00271   bool interaction_enabled_;
00272 
00273   bool debug_mode_;
00274 
00275   Ogre::MaterialPtr fallback_pick_material_;
00276   Ogre::Technique *fallback_pick_technique_;
00277   Ogre::Technique *fallback_black_technique_;
00278   Ogre::Technique *fallback_depth_technique_;
00279   Ogre::Technique *fallback_pick_cull_technique_;
00280   Ogre::Technique *fallback_black_cull_technique_;
00281   Ogre::Technique *fallback_depth_cull_technique_;
00282 
00283   uint32_t texture_size_;
00284 
00285   PropertyTreeModel* property_model_;
00286 
00287   typedef std::map<std::string, ros::Publisher> PublisherMap;
00288   PublisherMap debug_publishers_;
00289 };
00290 
00291 } // namespace rviz
00292 
00293 #endif // RVIZ_SELECTION_MANAGER_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31