point_visual.h
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 rviz
00018 {
00019 
00020 
00021 // Each instance of PointStampedVisual represents the visualization of a single
00022 // sensor_msgs::Point message.  Currently it just shows an arrow with
00023 // the direction and magnitude of the acceleration vector, but could
00024 // easily be expanded to include more of the message data.
00025 class PointStampedVisual
00026 {
00027 public:
00028     // Constructor.  Creates the visual stuff and puts it into the
00029     // scene, but in an unconfigured state.
00030     PointStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
00031 
00032     // Destructor.  Removes the visual stuff from the scene.
00033     virtual ~PointStampedVisual();
00034 
00035     // set rainbow color
00036     void getRainbowColor(float value, Ogre::ColourValue& color);
00037     // Configure the visual to show the data in the message.
00038     void setMessage( const geometry_msgs::PointStamped::ConstPtr& msg  );
00039 
00040     // Set the pose of the coordinate frame the message refers to.
00041     // These could be done inside setMessage(), but that would require
00042     // calls to FrameManager and error handling inside setMessage(),
00043     // which doesn't seem as clean.  This way PointStampedVisual is only
00044     // responsible for visualization.
00045     void setFramePosition( const Ogre::Vector3& position );
00046     void setFrameOrientation( const Ogre::Quaternion& orientation );
00047 
00048     // Set the color and alpha of the visual, which are user-editable
00049     // parameters and therefore don't come from the Point message.
00050     void setColor( float r, float g, float b, float a );
00051 
00052     void setRadius( float r );
00053 
00054 private:
00055     // The object implementing the point circle
00056     rviz::Shape* point_;
00057 
00058     // A SceneNode whose pose is set to match the coordinate frame of
00059     // the Point message header.
00060     Ogre::SceneNode* frame_node_;
00061 
00062     // The SceneManager, kept here only so the destructor can ask it to
00063     // destroy the ``frame_node_``.
00064     Ogre::SceneManager* scene_manager_;
00065 
00066     float radius_;
00067 
00068 };
00069 
00070 } // end namespace rviz
00071 
00072 #endif // POINT_VISUAL_H


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Aug 27 2015 15:02:27