normal_visual.h
Go to the documentation of this file.
00001 // -*- mode:c++ -*-
00002 #ifndef NORMAL_VISUAL_H
00003 #define NORMAL_VISUAL_H
00004 
00005 #include <OGRE/OgreVector3.h>
00006 #include <OGRE/OgreSceneNode.h>
00007 #include <OGRE/OgreSceneManager.h>
00008 
00009 #include <rviz/ogre_helpers/arrow.h>
00010 #include <geometry_msgs/Vector3.h>
00011 #include <sensor_msgs/PointCloud2.h>
00012 
00013 namespace jsk_rviz_plugin
00014 {
00015 
00016   class NormalVisual
00017   {
00018   public:
00019     NormalVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
00020 
00021     virtual ~NormalVisual();
00022 
00023     void setValues( float x, float y, float z, float normal_x, float normal_y, float  normal_z);
00024     void setFramePosition( const Ogre::Vector3& position );
00025     void setFrameOrientation( const Ogre::Quaternion& orientation );
00026     void setColor( float r, float g, float b, float a );
00027     void setScale( float scale );
00028 
00029   private:
00030     boost::shared_ptr<rviz::Arrow> normal_arrow_;
00031     Ogre::SceneNode* frame_node_;
00032     Ogre::SceneManager* scene_manager_;
00033   };
00034 }
00035 #endif


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44