#include <point_visual.h>
| Public Member Functions | |
| void | getRainbowColor (float value, Ogre::ColourValue &color) | 
| PointStampedVisual (Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node) | |
| void | setColor (float r, float g, float b, float a) | 
| void | setFrameOrientation (const Ogre::Quaternion &orientation) | 
| void | setFramePosition (const Ogre::Vector3 &position) | 
| void | setMessage (const geometry_msgs::PointStamped::ConstPtr &msg) | 
| void | setRadius (float r) | 
| virtual | ~PointStampedVisual () | 
| Private Attributes | |
| Ogre::SceneNode * | frame_node_ | 
| rviz::Shape * | point_ | 
| float | radius_ | 
| Ogre::SceneManager * | scene_manager_ | 
Definition at line 25 of file point_visual.h.
| rviz::PointStampedVisual::PointStampedVisual | ( | Ogre::SceneManager * | scene_manager, | 
| Ogre::SceneNode * | parent_node | ||
| ) | 
Definition at line 14 of file point_visual.cpp.
| rviz::PointStampedVisual::~PointStampedVisual | ( | ) |  [virtual] | 
Definition at line 32 of file point_visual.cpp.
| void rviz::PointStampedVisual::getRainbowColor | ( | float | value, | 
| Ogre::ColourValue & | color | ||
| ) | 
| void rviz::PointStampedVisual::setColor | ( | float | r, | 
| float | g, | ||
| float | b, | ||
| float | a | ||
| ) | 
Definition at line 65 of file point_visual.cpp.
| void rviz::PointStampedVisual::setFrameOrientation | ( | const Ogre::Quaternion & | orientation | ) | 
Definition at line 59 of file point_visual.cpp.
| void rviz::PointStampedVisual::setFramePosition | ( | const Ogre::Vector3 & | position | ) | 
Definition at line 54 of file point_visual.cpp.
| void rviz::PointStampedVisual::setMessage | ( | const geometry_msgs::PointStamped::ConstPtr & | msg | ) | 
Definition at line 42 of file point_visual.cpp.
| void rviz::PointStampedVisual::setRadius | ( | float | r | ) | 
Definition at line 70 of file point_visual.cpp.
| Ogre::SceneNode* rviz::PointStampedVisual::frame_node_  [private] | 
Definition at line 60 of file point_visual.h.
| rviz::Shape* rviz::PointStampedVisual::point_  [private] | 
Definition at line 56 of file point_visual.h.
| float rviz::PointStampedVisual::radius_  [private] | 
Definition at line 66 of file point_visual.h.
| Ogre::SceneManager* rviz::PointStampedVisual::scene_manager_  [private] | 
Definition at line 64 of file point_visual.h.