00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef RVIZ_SELECTION_MANAGER_H
00031 #define RVIZ_SELECTION_MANAGER_H
00032
00033 #include "forwards.h"
00034 #include "rviz/properties/forwards.h"
00035
00036 #include <boost/shared_ptr.hpp>
00037 #include <boost/unordered_map.hpp>
00038 #include <boost/signals.hpp>
00039 #include <boost/thread/recursive_mutex.hpp>
00040
00041 #include <OGRE/OgreTexture.h>
00042 #include <OGRE/OgreMaterial.h>
00043 #include <OGRE/OgrePixelFormat.h>
00044 #include <OGRE/OgreMovableObject.h>
00045
00046 #include <vector>
00047 #include <set>
00048
00049 #include <ros/console.h>
00050
00051
00052
00053 namespace ogre_tools
00054 {
00055 class Object;
00056 }
00057
00058 namespace Ogre
00059 {
00060 class SceneManager;
00061 class Viewport;
00062 class WireBoundingBox;
00063 class SceneNode;
00064 class Material;
00065 class PixelBox;
00066 class Rectangle2D;
00067 class MovableObject;
00068 }
00069
00070 namespace rviz
00071 {
00072
00073 class ViewportMouseEvent;
00074 class VisualizationManager;
00075 class PropertyManager;
00076
00077 inline uint32_t colorToHandle(Ogre::PixelFormat fmt, uint32_t col)
00078 {
00079 uint32_t handle = 0;
00080 if (fmt == Ogre::PF_A8R8G8B8 || fmt == Ogre::PF_X8R8G8B8)
00081 {
00082 handle = col & 0x00ffffff;
00083 }
00084 else if (fmt == Ogre::PF_R8G8B8A8)
00085 {
00086 handle = col >> 8;
00087 }
00088 else
00089 {
00090 ROS_DEBUG("Incompatible pixel format [%d]", fmt);
00091 }
00092
00093 return handle;
00094 }
00095
00096 typedef std::vector<Ogre::AxisAlignedBox> V_AABB;
00097
00098 class SelectionHandler
00099 {
00100 public:
00101 typedef std::vector<PropertyBaseWPtr> V_Property;
00102
00103 SelectionHandler();
00104 virtual ~SelectionHandler();
00105
00106 void initialize(VisualizationManager* manager);
00107 void addTrackedObject(Ogre::MovableObject* object);
00108 void removeTrackedObject(Ogre::MovableObject* object);
00109
00110 virtual void updateTrackedBoxes();
00111
00112 virtual void createProperties(const Picked& obj, PropertyManager* property_manager) {}
00113 virtual void destroyProperties(const Picked& obj, PropertyManager* property_manager);
00114 virtual void updateProperties();
00115
00116 virtual bool needsAdditionalRenderPass(uint32_t pass)
00117 {
00118 return false;
00119 }
00120
00121 virtual void preRenderPass(uint32_t pass);
00122 virtual void postRenderPass(uint32_t pass);
00123
00124 virtual void getAABBs(const Picked& obj, V_AABB& aabbs);
00125
00126 virtual void onSelect(const Picked& obj);
00127 virtual void onDeselect(const Picked& obj);
00128
00129 protected:
00130 void createBox(const std::pair<CollObjectHandle, uint64_t>& handles, const Ogre::AxisAlignedBox& aabb, const std::string& material_name);
00131 void destroyBox(const std::pair<CollObjectHandle, uint64_t>& handles);
00132
00133 V_Property properties_;
00134
00135 typedef std::map<std::pair<CollObjectHandle, uint64_t>, std::pair<Ogre::SceneNode*, Ogre::WireBoundingBox*> > M_HandleToBox;
00136 M_HandleToBox boxes_;
00137
00138 VisualizationManager* manager_;
00139
00140 typedef std::set<Ogre::MovableObject*> S_Movable;
00141 S_Movable tracked_objects_;
00142
00143 class Listener : public Ogre::MovableObject::Listener
00144 {
00145 public:
00146 Listener(SelectionHandler* handler)
00147 : handler_(handler)
00148 {}
00149 virtual void objectMoved(Ogre::MovableObject* object)
00150 {
00151 handler_->updateTrackedBoxes();
00152 }
00153
00154 virtual void objectDestroyed(Ogre::MovableObject* object)
00155 {
00156 handler_->removeTrackedObject(object);
00157 }
00158
00159 SelectionHandler* handler_;
00160 };
00161 typedef boost::shared_ptr<Listener> ListenerPtr;
00162 ListenerPtr listener_;
00163
00164 friend class SelectionManager;
00165 };
00166 typedef boost::shared_ptr<SelectionHandler> SelectionHandlerPtr;
00167 typedef std::vector<SelectionHandlerPtr> V_SelectionHandler;
00168 typedef std::set<SelectionHandlerPtr> S_SelectionHandler;
00169
00170
00171 struct SelectionSettingArgs
00172 {
00173 SelectionSettingArgs()
00174 {}
00175 };
00176 typedef boost::signal<void (const SelectionSettingArgs&)> SelectionSettingSignal;
00177
00178 struct SelectionSetArgs
00179 {
00180 SelectionSetArgs(const M_Picked& old_selection, const M_Picked& new_selection)
00181 : old_selection_(old_selection)
00182 , new_selection_(new_selection)
00183 {}
00184
00185 const M_Picked& old_selection_;
00186 const M_Picked& new_selection_;
00187 };
00188 typedef boost::signal<void (const SelectionSetArgs&)> SelectionSetSignal;
00189
00190 struct SelectionAddedArgs
00191 {
00192 SelectionAddedArgs(const M_Picked& added)
00193 : added_(added)
00194 {}
00195
00196 const M_Picked& added_;
00197 };
00198 typedef boost::signal<void (const SelectionAddedArgs&)> SelectionAddedSignal;
00199
00200 struct SelectionRemovedArgs
00201 {
00202 SelectionRemovedArgs(const M_Picked& removed)
00203 : removed_(removed)
00204 {}
00205
00206 const M_Picked& removed_;
00207 };
00208 typedef boost::signal<void (const SelectionRemovedArgs&)> SelectionRemovedSignal;
00209
00210 class SelectionManager
00211 {
00212 public:
00213 enum SelectType
00214 {
00215 Add,
00216 Remove,
00217 Replace
00218 };
00219
00220 SelectionManager(VisualizationManager* manager);
00221 ~SelectionManager();
00222
00223 void initialize();
00224
00225 void clearHandlers();
00226 void addObject(CollObjectHandle obj, const SelectionHandlerPtr& handler);
00227 void removeObject(CollObjectHandle obj);
00228
00229 void highlight(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
00230 void removeHighlight();
00231
00232 void select(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, SelectType type);
00233
00234 CollObjectHandle createCollisionForObject(ogre_tools::Object* obj, const SelectionHandlerPtr& handler, CollObjectHandle coll = 0);
00235 CollObjectHandle createCollisionForEntity(Ogre::Entity* entity, const SelectionHandlerPtr& handler, CollObjectHandle coll = 0);
00236
00237 void update();
00238
00239 void setSelection(const M_Picked& objs);
00240 void addSelection(const M_Picked& objs);
00241 void removeSelection(const M_Picked& objs);
00242 const M_Picked& getSelection() { return selection_; }
00243
00244 SelectionHandlerPtr getHandler(CollObjectHandle obj);
00245
00246 void addPickTechnique(CollObjectHandle handle, const Ogre::MaterialPtr& material);
00247
00248 inline CollObjectHandle createHandle()
00249 {
00250 if (uid_counter_ > 0x00ffffff)
00251 {
00252 uid_counter_ = 0;
00253 }
00254
00255 uint32_t handle = 0;
00256
00257 do
00258 {
00259 handle = (++uid_counter_)<<4;
00260 handle ^= 0x00707070;
00261 handle &= 0x00ffffff;
00262 } while (objects_.find(handle) != objects_.end());
00263
00264 return handle;
00265 }
00266
00267 void focusOnSelection();
00268
00269 protected:
00270 std::pair<Picked, bool> addSelection(const Picked& obj);
00271 void removeSelection(const Picked& obj);
00272
00273 void setHighlightRect(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2);
00274 void pick(Ogre::Viewport* viewport, int x1, int y1, int x2, int y2, M_Picked& results);
00275 void renderAndUnpack(Ogre::Viewport* viewport, uint32_t pass, int x1, int y1, int x2, int y2, V_Pixel& pixels);
00276 void unpackColors(Ogre::Viewport* pick_viewport, Ogre::Viewport* render_viewport, const Ogre::PixelBox& box, int x1, int y1, int x2, int y2, V_Pixel& pixels);
00277
00278 VisualizationManager* vis_manager_;
00279
00280 boost::recursive_mutex global_mutex_;
00281
00282 typedef boost::unordered_map<CollObjectHandle, SelectionHandlerPtr> M_CollisionObjectToSelectionHandler;
00283 M_CollisionObjectToSelectionHandler objects_;
00284
00285 bool highlight_enabled_;
00286
00287 struct Highlight
00288 {
00289 int x1;
00290 int y1;
00291 int x2;
00292 int y2;
00293 Ogre::Viewport* viewport;
00294 };
00295 Highlight highlight_;
00296
00297 M_Picked selection_;
00298
00299 const static uint32_t s_num_render_textures_ = 2;
00300 const static uint32_t s_render_texture_size_ = 1024;
00301 Ogre::TexturePtr render_textures_[s_num_render_textures_];
00302 Ogre::PixelBox pixel_boxes_[s_num_render_textures_];
00303
00304 uint32_t uid_counter_;
00305
00306 Ogre::Rectangle2D* highlight_rectangle_;
00307 Ogre::SceneNode* highlight_node_;
00308
00309 V_Pixel pixel_buffer_;
00310
00311 #if defined(PICKING_DEBUG)
00312 Ogre::SceneNode* debug_nodes_[s_num_render_textures_];
00313 #endif
00314
00315 public:
00316 SelectionSetSignal& getSelectionSetSignal() { return selection_set_; }
00317 SelectionSettingSignal& getSelectionSettingSignal() { return selection_setting_; }
00318 SelectionAddedSignal& getSelectionAddedSignal() { return selection_added_; }
00319 SelectionRemovedSignal& getSelectionRemovedSignal() { return selection_removed_; }
00320
00321 protected:
00322 SelectionSettingSignal selection_setting_;
00323 SelectionSetSignal selection_set_;
00324 SelectionAddedSignal selection_added_;
00325 SelectionRemovedSignal selection_removed_;
00326 };
00327
00328 }
00329
00330 #endif // RVIZ_SELECTION_MANAGER_H