display.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_DISPLAY_H
00031 #define RVIZ_DISPLAY_H
00032 
00033 #include <QObject>
00034 
00035 #include "properties/forwards.h"
00036 #include "status_level.h"
00037 
00038 #include <string>
00039 #include <boost/function.hpp>
00040 
00041 #include <ros/ros.h>
00042 
00043 namespace Ogre
00044 {
00045 class SceneManager;
00046 }
00047 
00048 namespace rviz
00049 {
00050 
00051 class PropertyManager;
00052 class CategoryProperty;
00053 class BoolProperty;
00054 
00055 class VisualizationManager;
00056 
00057 class Display;
00058 
00066 class Display: public QObject
00067 {
00068 Q_OBJECT
00069 public:
00070   Display();
00071   virtual ~Display();
00072 
00074   void initialize( const std::string& name, VisualizationManager* manager );
00075 
00078   virtual void onInitialize() {}
00079 
00084   void enable( bool force = false );
00089   void disable( bool force = false );
00090 
00091   bool isEnabled() { return enabled_; }
00092   void setEnabled(bool enable, bool force = false);
00093 
00094   const std::string& getName() const { return name_; }
00095   void setName(const std::string& name);
00096 
00101   virtual void update( float wall_dt, float ros_dt ) {}
00102 
00104 
00108   void setRenderCallback( boost::function<void ()> func );
00109 
00111   void setLockRenderCallback( boost::function<void ()> func );
00113   void setUnlockRenderCallback( boost::function<void ()> func );
00114 
00120   void setPropertyManager( PropertyManager* manager, const CategoryPropertyWPtr& parent );
00121 
00127   virtual void createProperties() {}
00128 
00130   void setTargetFrame( const std::string& frame );
00131 
00135   virtual void targetFrameChanged() = 0;
00136 
00141   void setFixedFrame( const std::string& frame );
00142 
00146   virtual void fixedFrameChanged() = 0;
00147 
00151   virtual void reset();
00152 
00153   void setStatus(StatusLevel level, const std::string& name, const std::string& text);
00154   void deleteStatus(const std::string& name);
00155   void clearStatuses();
00156   StatusLevel getStatus();
00157 
00158 Q_SIGNALS:
00160   void stateChanged( Display* );
00161 
00162 protected:
00164   virtual void onEnable() = 0;
00166   virtual void onDisable() = 0;
00167 
00169 
00173   void causeRender();
00174 
00176   void lockRender();
00178   void unlockRender();
00179 
00180   VisualizationManager* vis_manager_;
00181 
00182   Ogre::SceneManager* scene_manager_;                 
00183   std::string name_;                                  
00184   bool enabled_;                                      
00185   StatusLevel status_;
00186 
00187   ros::NodeHandle update_nh_;
00188   ros::NodeHandle threaded_nh_;
00189 
00190   std::string target_frame_;                          
00191   std::string fixed_frame_;                           
00192 
00193   boost::function<void ()> render_callback_;          
00194   boost::function<void ()> render_lock_;              
00195   boost::function<void ()> render_unlock_;            
00196 
00197   std::string property_prefix_;                       
00198 
00199   PropertyManager* property_manager_;                 
00200   CategoryPropertyWPtr parent_category_;                 
00201   StatusPropertyWPtr status_property_;
00202 
00203   friend class RenderAutoLock;
00204 };
00205 
00213 class RenderAutoLock
00214 {
00215 public:
00216   RenderAutoLock( Display* display )
00217   : display_( display )
00218   {
00219     display_->lockRender();
00220   }
00221 
00222   ~RenderAutoLock()
00223   {
00224     display_->unlockRender();
00225   }
00226 
00227 private:
00228   Display* display_;
00229 };
00230 
00231 } // namespace rviz
00232 
00233 #endif


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52