tf_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_TF_DISPLAY_H
00031 #define RVIZ_TF_DISPLAY_H
00032 
00033 #include "rviz/display.h"
00034 #include "rviz/properties/forwards.h"
00035 
00036 #include <OGRE/OgreVector3.h>
00037 #include <OGRE/OgreQuaternion.h>
00038 
00039 #include <map>
00040 #include <set>
00041 
00042 namespace rviz
00043 {
00044 class Arrow;
00045 class Axes;
00046 class MovableText;
00047 }
00048 
00049 namespace Ogre
00050 {
00051 class SceneNode;
00052 }
00053 
00054 namespace rviz
00055 {
00056 
00057 class BoolProperty;
00058 class Vector3Property;
00059 class QuaternionProperty;
00060 class FloatProperty;
00061 class CategoryProperty;
00062 class StringProperty;
00063 
00064 struct FrameInfo;
00065 typedef std::set<FrameInfo*> S_FrameInfo;
00066 
00071 class TFDisplay : public Display
00072 {
00073 public:
00074   TFDisplay();
00075   virtual ~TFDisplay();
00076 
00077   virtual void onInitialize();
00078 
00079   bool getShowNames() { return show_names_; }
00080   void setShowNames( bool show );
00081 
00082   bool getShowAxes() { return show_axes_; }
00083   void setShowAxes( bool show );
00084 
00085   bool getShowArrows() { return show_arrows_; }
00086   void setShowArrows( bool show );
00087 
00088   float getUpdateRate() { return update_rate_; }
00089   void setUpdateRate( float rate );
00090 
00091   bool getAllEnabled() { return all_enabled_; }
00092   void setAllEnabled(bool enabled);
00093 
00094   float getFrameTimeout() { return frame_timeout_; }
00095   void setFrameTimeout(float timeout);
00096 
00097   float getScale() { return scale_; } 
00098   void setScale(float scale); 
00099 
00100   void setFrameEnabled(FrameInfo* frame, bool enabled);
00101 
00102   // Overrides from Display
00103   virtual void update(float wall_dt, float ros_dt);
00104   virtual void fixedFrameChanged();
00105   virtual void createProperties();
00106   virtual void reset();
00107 
00108 protected:
00109   void updateFrames();
00110   FrameInfo* createFrame(const std::string& frame);
00111   void updateFrame(FrameInfo* frame);
00112   void deleteFrame(FrameInfo* frame, bool delete_properties);
00113 
00114   FrameInfo* getFrameInfo(const std::string& frame);
00115 
00116   void clear();
00117 
00118   // overrides from Display
00119   virtual void onEnable();
00120   virtual void onDisable();
00121 
00122   Ogre::SceneNode* root_node_;
00123   Ogre::SceneNode* names_node_;
00124   Ogre::SceneNode* arrows_node_;
00125   Ogre::SceneNode* axes_node_;
00126 
00127   typedef std::map<std::string, FrameInfo*> M_FrameInfo;
00128   M_FrameInfo frames_;
00129 
00130   float update_timer_;
00131   float update_rate_;
00132 
00133   bool show_names_;
00134   bool show_arrows_;
00135   bool show_axes_;
00136   float frame_timeout_;
00137   bool all_enabled_;
00138 
00139   float scale_;
00140 
00141   BoolPropertyWPtr show_names_property_;
00142   BoolPropertyWPtr show_arrows_property_;
00143   BoolPropertyWPtr show_axes_property_;
00144   FloatPropertyWPtr update_rate_property_;
00145   FloatPropertyWPtr frame_timeout_property_;
00146   BoolPropertyWPtr all_enabled_property_;
00147 
00148   FloatPropertyWPtr scale_property_;
00149 
00150   CategoryPropertyWPtr frames_category_;
00151   CategoryPropertyWPtr tree_category_;
00152 };
00153 
00154 } // namespace rviz
00155 
00156  #endif
00157 


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