Go to the documentation of this file.
2 #ifndef NORMAL_VISUAL_H
3 #define NORMAL_VISUAL_H
5 #include <OGRE/OgreVector3.h>
6 #include <OGRE/OgreSceneNode.h>
7 #include <OGRE/OgreSceneManager.h>
10 #include <geometry_msgs/Vector3.h>
11 #include <sensor_msgs/PointCloud2.h>
20 NormalVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
24 void setValues(
float x,
float y,
float z,
float normal_x,
float normal_y,
float normal_z);
27 void setColor(
float r,
float g,
float b,
float a );
31 #if ROS_VERSION_MINIMUM(1,12,0)
Ogre::SceneManager * scene_manager_
Ogre::SceneNode * frame_node_
NormalVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
void setColor(float r, float g, float b, float a)
void setScale(float scale)
void setFrameOrientation(const Ogre::Quaternion &orientation)
void setValues(float x, float y, float z, float normal_x, float normal_y, float normal_z)
void setFramePosition(const Ogre::Vector3 &position)
boost::shared_ptr< rviz::Arrow > normal_arrow_
jsk_rviz_plugins
Author(s): Kei Okada
, Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Tue Dec 10 2024 03:48:24