normal_visual.h
Go to the documentation of this file.
1 // -*- mode:c++ -*-
2 #ifndef NORMAL_VISUAL_H
3 #define NORMAL_VISUAL_H
4 
5 #include <OGRE/OgreVector3.h>
6 #include <OGRE/OgreSceneNode.h>
7 #include <OGRE/OgreSceneManager.h>
8 
10 #include <geometry_msgs/Vector3.h>
11 #include <sensor_msgs/PointCloud2.h>
12 #include <ros/ros.h>
13 
14 namespace jsk_rviz_plugins
15 {
16 
18  {
19  public:
20  NormalVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
21 
22  virtual ~NormalVisual();
23 
24  void setValues( float x, float y, float z, float normal_x, float normal_y, float normal_z);
25  void setFramePosition( const Ogre::Vector3& position );
26  void setFrameOrientation( const Ogre::Quaternion& orientation );
27  void setColor( float r, float g, float b, float a );
28  void setScale( float scale );
29 
30  private:
31 #if ROS_VERSION_MINIMUM(1,12,0)
32  std::shared_ptr<rviz::Arrow> normal_arrow_;
33 #else
35 #endif
36  Ogre::SceneNode* frame_node_;
37  Ogre::SceneManager* scene_manager_;
38  };
39 }
40 #endif
void setFramePosition(const Ogre::Vector3 &position)
void setValues(float x, float y, float z, float normal_x, float normal_y, float normal_z)
Ogre::SceneManager * scene_manager_
Definition: normal_visual.h:37
boost::shared_ptr< rviz::Arrow > normal_arrow_
Definition: normal_visual.h:34
Ogre::SceneNode * frame_node_
Definition: normal_visual.h:36
NormalVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
void setColor(float r, float g, float b, float a)
void setFrameOrientation(const Ogre::Quaternion &orientation)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18