$search
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 <QObject> 00034 00035 #include "forwards.h" 00036 #include "selection_handler.h" 00037 #include "rviz/properties/forwards.h" 00038 00039 #include <boost/shared_ptr.hpp> 00040 #include <boost/unordered_map.hpp> 00041 #include <boost/thread/recursive_mutex.hpp> 00042 00043 #include <OGRE/OgreTexture.h> 00044 #include <OGRE/OgreMaterial.h> 00045 #include <OGRE/OgreMaterialManager.h> 00046 #include <OGRE/OgreMovableObject.h> 00047 #include <OGRE/OgreRenderQueueListener.h> 00048 00049 #include <vector> 00050 #include <set> 00051 00052 namespace ogre_tools 00053 { 00054 class Object; 00055 } 00056 00057 namespace Ogre 00058 { 00059 class SceneManager; 00060 class Viewport; 00061 class WireBoundingBox; 00062 class SceneNode; 00063 class Material; 00064 class PixelBox; 00065 class Rectangle2D; 00066 class MovableObject; 00067 } 00068 00069 namespace rviz 00070 { 00071 class ViewportMouseEvent; 00072 class VisualizationManager; 00073 class PropertyManager; 00074 00075 class SelectionManager: public QObject, public Ogre::MaterialManager::Listener, public Ogre::RenderQueueListener 00076 { 00077 Q_OBJECT 00078 public: 00079 enum SelectType 00080 { 00081 Add, 00082 Remove, 00083 Replace 00084 }; 00085 00086 SelectionManager(VisualizationManager* manager); 00087 ~SelectionManager(); 00088 00089 void initialize( bool debug = false ); 00090 00091 void clearHandlers(); 00092 void addObject(CollObjectHandle obj, const SelectionHandlerPtr& handler); 00093 void removeObject(CollObjectHandle obj); 00094 00095 // control the highlight box being displayed while selecting 00096 void highlight(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2); 00097 void removeHighlight(); 00098 00099 // select all objects in bounding box 00100 void select(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, SelectType type); 00101 00102 // @return handles of all objects in the given bounding box 00103 // @param single_render_pass only perform one rendering pass (point cloud selecting won't work) 00104 void pick(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, M_Picked& results, bool single_render_pass=false ); 00105 00106 // create handle, add or modify the picking scheme of the object's material accordingly 00107 CollObjectHandle createCollisionForObject(ogre_tools::Object* obj, const SelectionHandlerPtr& handler, CollObjectHandle coll = 0); 00108 CollObjectHandle createCollisionForEntity(Ogre::Entity* entity, const SelectionHandlerPtr& handler, CollObjectHandle coll = 0); 00109 00110 void update(); 00111 00112 // modify the list of currently selected objects 00113 void setSelection(const M_Picked& objs); 00114 void addSelection(const M_Picked& objs); 00115 void removeSelection(const M_Picked& objs); 00116 const M_Picked& getSelection() { return selection_; } 00117 00118 SelectionHandlerPtr getHandler(CollObjectHandle obj); 00119 00120 // modify the given material so it contains a technique for the picking scheme that uses the given handle 00121 Ogre::Technique *addPickTechnique(CollObjectHandle handle, const Ogre::MaterialPtr& material); 00122 00123 // if a material does not support the picking scheme, paint it black 00124 virtual Ogre::Technique* handleSchemeNotFound(unsigned short scheme_index, 00125 const Ogre::String& scheme_name, 00126 Ogre::Material* original_material, 00127 unsigned short lod_index, 00128 const Ogre::Renderable* rend); 00129 00130 // create a new unique handle 00131 CollObjectHandle createHandle(); 00132 00133 // tell all handlers that interactive mode is active/inactive 00134 void enableInteraction( bool enable ); 00135 bool getInteractionEnabled() { return interaction_enabled_; } 00136 00137 // tell the view controller to look at the selection 00138 void focusOnSelection(); 00139 00140 // change the size of the off-screen selection buffer texture 00141 void setTextureSize( unsigned size ); 00142 00146 bool get3DPoint( Ogre::Viewport* viewport, int x, int y, Ogre::Vector3& result_point ); 00147 00148 // Implementation for Ogre::RenderQueueListener. 00149 void renderQueueStarted( uint8_t queueGroupId, 00150 const std::string& invocation, 00151 bool& skipThisInvocation ); 00152 00153 Q_SIGNALS: 00154 void selectionSet( const M_Picked& old_selection, const M_Picked& new_selection ); 00155 void selectionSetting(); 00156 void selectionAdded( const M_Picked& added ); 00157 void selectionRemoved( const M_Picked& removed ); 00158 00159 protected: 00160 std::pair<Picked, bool> addSelection(const Picked& obj); 00161 void removeSelection(const Picked& obj); 00162 00163 void setHighlightRect(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2); 00164 00166 void renderAndUnpack(Ogre::Viewport* viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_Pixel& pixels); 00167 00169 bool render( Ogre::Viewport* viewport, Ogre::TexturePtr tex, 00170 int x1, int y1, int x2, int y2, 00171 Ogre::PixelBox& dst_box, std::string material_scheme, 00172 unsigned texture_size ); 00173 00174 void unpackColors(const Ogre::PixelBox& box, V_Pixel& pixels); 00175 00176 void initDepthFinder(); 00177 00178 // Set the visibility of the debug windows. If debug_mode_ is false, this has no effect. 00179 void setDebugVisibility( bool visible ); 00180 00181 VisualizationManager* vis_manager_; 00182 00183 boost::recursive_mutex global_mutex_; 00184 00185 typedef boost::unordered_map<CollObjectHandle, SelectionHandlerPtr> M_CollisionObjectToSelectionHandler; 00186 M_CollisionObjectToSelectionHandler objects_; 00187 00188 bool highlight_enabled_; 00189 00190 struct Highlight 00191 { 00192 int x1; 00193 int y1; 00194 int x2; 00195 int y2; 00196 Ogre::Viewport* viewport; 00197 }; 00198 Highlight highlight_; 00199 00200 M_Picked selection_; 00201 00202 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) 00203 Ogre::TexturePtr render_textures_[s_num_render_textures_]; 00204 Ogre::PixelBox pixel_boxes_[s_num_render_textures_]; 00205 00206 // Graphics card -based depth finding of clicked points. 00207 Ogre::TexturePtr depth_render_texture_; 00208 uint32_t depth_texture_size_; 00209 Ogre::SceneNode* debug_depth_node_; 00210 Ogre::MaterialPtr debug_depth_material_; 00211 Ogre::PixelBox depth_pixel_box_; 00212 00213 uint32_t uid_counter_; 00214 00215 Ogre::Rectangle2D* highlight_rectangle_; 00216 Ogre::SceneNode* highlight_node_; 00217 Ogre::Camera *camera_; 00218 00219 V_Pixel pixel_buffer_; 00220 00221 bool interaction_enabled_; 00222 00223 Ogre::SceneNode* debug_nodes_[s_num_render_textures_]; 00224 Ogre::MaterialPtr debug_material_[s_num_render_textures_]; 00225 bool debug_mode_; 00226 00227 Ogre::MaterialPtr fallback_pick_material_; 00228 Ogre::Technique *fallback_pick_technique_; 00229 00230 uint32_t texture_size_; 00231 }; 00232 00233 } // namespace rviz 00234 00235 #endif // RVIZ_SELECTION_MANAGER_H