visualization_manager.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 
00031 #ifndef RVIZ_VISUALIZATION_MANAGER_H_
00032 #define RVIZ_VISUALIZATION_MANAGER_H_
00033 
00034 #include <QObject>
00035 #include <QTimer>
00036 
00037 #include "rviz/helpers/color.h"
00038 #include "rviz/properties/forwards.h"
00039 
00040 #include <boost/thread.hpp>
00041 
00042 #include <vector>
00043 #include <map>
00044 #include <set>
00045 
00046 #include <ros/ros.h>
00047 #include <ros/callback_queue.h>
00048 #include <ros/time.h>
00049 
00050 #include <pluginlib/class_loader.h>
00051 
00052 class QKeyEvent;
00053 
00054 namespace Ogre
00055 {
00056 class Root;
00057 class SceneManager;
00058 class SceneNode;
00059 }
00060 
00061 namespace tf
00062 {
00063 class TransformListener;
00064 }
00065 
00066 namespace rviz
00067 {
00068 
00069 class Config;
00070 class PropertyManager;
00071 class SelectionManager;
00072 class RenderPanel;
00073 class Display;
00074 class Tool;
00075 class ViewportMouseEvent;
00076 class WindowManagerInterface;
00077 class PluginManager;
00078 class PluginStatus;
00079 class FrameManager;
00080 class ViewController;
00081 typedef boost::shared_ptr<FrameManager> FrameManagerPtr;
00082 
00083 class DisplayWrapper;
00084 typedef std::vector<DisplayWrapper*> V_DisplayWrapper;
00085 
00086 class DisplayTypeInfo;
00087 typedef boost::shared_ptr<DisplayTypeInfo> DisplayTypeInfoPtr;
00088 
00103 class VisualizationManager: public QObject
00104 {
00105 Q_OBJECT
00106 public:
00115   VisualizationManager(RenderPanel* render_panel, WindowManagerInterface* wm = 0);
00116 
00121   virtual ~VisualizationManager();
00122 
00128   void initialize(const StatusCallback& cb = StatusCallback(), bool verbose=false);
00129 
00134   void startUpdate();
00135 
00144   DisplayWrapper* createDisplay( const std::string& class_lookup_name, const std::string& name, bool enabled );
00145 
00150   void removeDisplay( DisplayWrapper* display );
00151 
00157   void removeDisplay( const std::string& name );
00158 
00162   void removeAllDisplays();
00163 
00169   template< class T >
00170   T* createTool( const std::string& name, char shortcut_key )
00171   {
00172     T* tool = new T( name, shortcut_key, this );
00173     addTool( tool );
00174 
00175     return tool;
00176   }
00177 
00182   void addTool( Tool* tool );
00183 
00188   Tool* getCurrentTool() { return current_tool_; }
00189 
00195   Tool* getTool( int index );
00196 
00204   void setCurrentTool( Tool* tool );
00205 
00217   void setDefaultTool( Tool* tool );
00218 
00223   Tool* getDefaultTool() { return default_tool_; }
00224 
00235   void loadDisplayConfig( const boost::shared_ptr<Config>& config, const StatusCallback& cb = StatusCallback() );
00236 
00245   void saveDisplayConfig( const boost::shared_ptr<Config>& config );
00246 
00260   void setTargetFrame( const std::string& frame );
00261 
00266   std::string getTargetFrame();
00267 
00273   void setFixedFrame( const std::string& frame );
00274 
00279   const std::string& getFixedFrame() { return fixed_frame_; }
00280 
00285   DisplayWrapper* getDisplayWrapper( const std::string& name );
00286 
00293   DisplayWrapper* getDisplayWrapper( Display* display );
00294 
00299   PropertyManager* getPropertyManager() { return property_manager_; }
00300 
00305   PropertyManager* getToolPropertyManager() { return tool_property_manager_; }
00306 
00314   bool isValidDisplay( const DisplayWrapper* display );
00315 
00319   tf::TransformListener* getTFClient();
00320 
00324   Ogre::SceneManager* getSceneManager() { return scene_manager_; }
00325 
00329   RenderPanel* getRenderPanel() { return render_panel_; }
00330 
00331   typedef std::set<std::string> S_string;
00332 
00336   void getDisplayNames(S_string& displays);
00337 
00341   V_DisplayWrapper& getDisplays() { return displays_; }
00342 
00346   void resetDisplays();
00347 
00351   double getWallClock();
00352 
00356   double getROSTime();
00357 
00361   double getWallClockElapsed();
00362 
00366   double getROSTimeElapsed();
00367 
00375   void handleChar( QKeyEvent* event, RenderPanel* panel );
00376 
00384   void handleMouseEvent( ViewportMouseEvent& event );
00385 
00389   void setBackgroundColor(const Color& c);
00390 
00394   const Color& getBackgroundColor();
00395 
00399   void resetTime();
00400 
00404   ViewController* getCurrentViewController() { return view_controller_; }
00405 
00410   std::string getCurrentViewControllerType();
00411 
00431   bool setCurrentViewControllerType(const std::string& type);
00432 
00436   SelectionManager* getSelectionManager() { return selection_manager_; }
00437 
00441   void lockRender() { render_mutex_.lock(); }
00442 
00446   void unlockRender() { render_mutex_.unlock(); }
00447 
00452   void queueRender();
00453 
00457   WindowManagerInterface* getWindowManager() { return window_manager_; }
00458 
00462   ros::CallbackQueueInterface* getUpdateQueue() { return ros::getGlobalCallbackQueue(); }
00463 
00467   ros::CallbackQueueInterface* getThreadedQueue() { return &threaded_queue_; }
00468 
00471   pluginlib::ClassLoader<Display>* getDisplayClassLoader() { return display_class_loader_; }
00472 
00474   FrameManager* getFrameManager() { return frame_manager_.get(); }
00475 
00481   uint64_t getFrameCount() { return frame_count_; }
00482 
00485   void notifyConfigChanged();
00486 
00487 Q_SIGNALS:
00489   void displayAdding( DisplayWrapper* );
00490 
00494   void displayAdded( DisplayWrapper* );
00495 
00497   void displayRemoving( DisplayWrapper* );
00498 
00501   void displayRemoved( DisplayWrapper* );
00502 
00504   void displaysRemoving( const V_DisplayWrapper& );
00505 
00507   void displaysRemoved( const V_DisplayWrapper& );
00508 
00515   void displaysConfigLoaded( const boost::shared_ptr<Config>& );
00516 
00523   void displaysConfigSaved( const boost::shared_ptr<Config>& );
00524 
00528   void toolAdded( Tool* );
00529 
00534   void toolChanged( Tool* );
00535 
00541   void viewControllerTypeAdded( const std::string& class_name, const std::string& name );
00542 
00546   void viewControllerChanged( ViewController* );
00547 
00551   void timeChanged();
00552 
00554   void configChanged();
00555 
00556 protected Q_SLOTS:
00566   void onUpdate();
00567 
00572   void onIdle();
00573 
00574   void onDisplayCreated( DisplayWrapper* wrapper );
00575 
00576 protected:
00581   bool addDisplay(DisplayWrapper* wrapper, bool enabled);
00582 
00583   void addViewController(const std::string& class_name, const std::string& name);
00584 
00585   void updateRelativeNode();
00586 
00587   void incomingROSTime();
00588 
00589   void updateTime();
00590   void updateFrames();
00591 
00592   void createColorMaterials();
00593 
00594   void threadedQueueThreadFunc();
00595 
00596   void onPluginUnloading(const PluginStatus& status);
00597 
00598   Ogre::Root* ogre_root_;                                 
00599   Ogre::SceneManager* scene_manager_;                     
00600 
00601   QTimer* update_timer_;                                 
00602   ros::Time last_update_ros_time_;                        
00603   ros::WallTime last_update_wall_time_;
00604 
00605   QTimer* idle_timer_; 
00606 
00607   ros::CallbackQueue threaded_queue_;
00608   boost::thread_group threaded_queue_threads_;
00609   ros::NodeHandle update_nh_;
00610   ros::NodeHandle threaded_nh_;
00611   volatile bool shutting_down_;
00612 
00613 
00614   V_DisplayWrapper displays_;                          
00615 
00616   typedef std::vector< Tool* > V_Tool;
00617   V_Tool tools_;
00618   Tool* current_tool_;
00619   Tool* default_tool_;
00620 
00621   std::string target_frame_;                              
00622   std::string fixed_frame_;                               
00623 
00624   PropertyManager* property_manager_;
00625   PropertyManager* tool_property_manager_;
00626   TFFramePropertyWPtr target_frame_property_;
00627   EditEnumPropertyWPtr fixed_frame_property_;
00628   StatusPropertyWPtr status_property_;
00629 
00630   V_string available_frames_;
00631 
00632   RenderPanel* render_panel_;
00633 
00634   ros::WallTime wall_clock_begin_;
00635   ros::Time ros_time_begin_;
00636   ros::WallDuration wall_clock_elapsed_;
00637   ros::Duration ros_time_elapsed_;
00638 
00639   Color background_color_;
00640   ColorPropertyWPtr background_color_property_;
00641 
00642   float time_update_timer_;
00643   float frame_update_timer_;
00644 
00645   ViewController* view_controller_;
00646 
00647   SelectionManager* selection_manager_;
00648 
00649   boost::mutex render_mutex_;
00650   uint32_t render_requested_;
00651   uint64_t frame_count_;
00652   ros::WallTime last_render_;
00653 
00654   WindowManagerInterface* window_manager_;
00655   
00656   pluginlib::ClassLoader<Display>* display_class_loader_;
00657 //  PluginManager* plugin_manager_;
00658   FrameManagerPtr frame_manager_;
00659 
00660   bool disable_update_;
00661   bool target_frame_is_fixed_frame_;
00662 
00663   Ogre::SceneNode *target_scene_node_;
00664 
00665   std::deque<ViewportMouseEvent> vme_queue_;
00666   boost::mutex vme_queue_mutex_;
00667 };
00668 
00669 }
00670 
00671 #endif /* RVIZ_VISUALIZATION_MANAGER_H_ */


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:33