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