Go to the documentation of this file.00001 #ifndef POINT_VISUAL_H
00002 #define POINT_VISUAL_H
00003 
00004 #include <geometry_msgs/PointStamped.h>
00005 
00006 namespace Ogre
00007 {
00008     class Vector3;
00009     class Quaternion;
00010 }
00011 
00012 namespace rviz
00013 {
00014     class Shape;
00015 }
00016 
00017 namespace jsk_rviz_plugin
00018 {
00019 
00020 
00021 
00022 
00023 
00024 
00025 class PointStampedVisual
00026 {
00027 public:
00028     
00029     
00030     PointStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
00031 
00032     
00033     virtual ~PointStampedVisual();
00034 
00035     
00036     void getRainbowColor(float value, Ogre::ColourValue& color);
00037     
00038     void setMessage( const geometry_msgs::PointStamped::ConstPtr& msg  );
00039 
00040     
00041     
00042     
00043     
00044     
00045     void setFramePosition( const Ogre::Vector3& position );
00046     void setFrameOrientation( const Ogre::Quaternion& orientation );
00047 
00048     
00049     
00050     void setColor( float r, float g, float b, float a );
00051 
00052     void setRadius( float r );
00053 
00054 private:
00055     
00056     rviz::Shape* point_;
00057 
00058     
00059     
00060     Ogre::SceneNode* frame_node_;
00061 
00062     
00063     
00064     Ogre::SceneManager* scene_manager_;
00065 
00066     float radius_;
00067 
00068 };
00069 
00070 } 
00071 
00072 #endif // POINT_VISUAL_H