robot_model_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_ROBOT_MODEL_DISPLAY_H
00031 #define RVIZ_ROBOT_MODEL_DISPLAY_H
00032 
00033 #include "rviz/display.h"
00034 #include "rviz/properties/forwards.h"
00035 
00036 #include <OGRE/OgreVector3.h>
00037 
00038 #include <map>
00039 
00040 namespace Ogre
00041 {
00042 class Entity;
00043 class SceneNode;
00044 }
00045 
00046 namespace rviz
00047 {
00048 class Axes;
00049 }
00050 
00051 namespace rviz
00052 {
00053 
00054 class Robot;
00055 
00060 class RobotModelDisplay : public Display
00061 {
00062 public:
00063   RobotModelDisplay();
00064   virtual ~RobotModelDisplay();
00065 
00066   void onInitialize();
00067 
00072   void setRobotDescription( const std::string& description_param );
00073 
00074   virtual void update(float wall_dt, float ros_dt);
00075 
00080   void setVisualVisible( bool visible );
00081 
00086   void setCollisionVisible( bool visible );
00087 
00092   void setUpdateRate( float rate );
00093 
00094   const std::string& getRobotDescription() { return description_param_; }
00095   float getUpdateRate() { return update_rate_; }
00096   bool isVisualVisible();
00097   bool isCollisionVisible();
00098 
00099   float getAlpha() { return alpha_; }
00100   void setAlpha( float alpha );
00101 
00102   const std::string& getTFPrefix() { return tf_prefix_; }
00103   void setTFPrefix(const std::string& prefix);
00104 
00105   void clear();
00106 
00107   // Overrides from Display
00108   virtual void fixedFrameChanged();
00109   virtual void createProperties();
00110   virtual void reset();
00111 
00113   virtual void hideVisible();
00114 
00116   virtual void restoreVisible();
00117 
00118 protected:
00119 
00123   void load();
00124 
00125   // overrides from Display
00126   virtual void onEnable();
00127   virtual void onDisable();
00128 
00129   std::string description_param_;             
00130 
00131   Robot* robot_;                              
00132 
00133   bool has_new_transforms_;                   
00134 
00135   float time_since_last_transform_;
00136   float update_rate_;
00137   float alpha_;
00138   std::string tf_prefix_;
00139 
00140   BoolPropertyWPtr visual_enabled_property_;
00141   BoolPropertyWPtr collision_enabled_property_;
00142   FloatPropertyWPtr update_rate_property_;
00143   StringPropertyWPtr robot_description_property_;
00144   FloatPropertyWPtr alpha_property_;
00145   StringPropertyWPtr tf_prefix_property_;
00146 
00147   std::string robot_description_;
00148 
00149   bool hidden_;
00150 };
00151 
00152 } // namespace rviz
00153 
00154  #endif
00155 


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