point_visual.h
Go to the documentation of this file.
1 #ifndef POINT_VISUAL_H
2 #define POINT_VISUAL_H
3 
4 #include <geometry_msgs/PointStamped.h>
5 
6 namespace Ogre
7 {
8  class Vector3;
9  class Quaternion;
10 }
11 
12 namespace rviz
13 {
14  class Shape;
15 }
16 
17 namespace rviz
18 {
19 
20 
21 // Each instance of PointStampedVisual represents the visualization of a single
22 // sensor_msgs::Point message. Currently it just shows an arrow with
23 // the direction and magnitude of the acceleration vector, but could
24 // easily be expanded to include more of the message data.
26 {
27 public:
28  // Constructor. Creates the visual stuff and puts it into the
29  // scene, but in an unconfigured state.
30  PointStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node );
31 
32  // Destructor. Removes the visual stuff from the scene.
33  virtual ~PointStampedVisual();
34 
35  // set rainbow color
36  void getRainbowColor(float value, Ogre::ColourValue& color);
37  // Configure the visual to show the data in the message.
38  void setMessage( const geometry_msgs::PointStamped::ConstPtr& msg );
39 
40  // Set the pose of the coordinate frame the message refers to.
41  // These could be done inside setMessage(), but that would require
42  // calls to FrameManager and error handling inside setMessage(),
43  // which doesn't seem as clean. This way PointStampedVisual is only
44  // responsible for visualization.
45  void setFramePosition( const Ogre::Vector3& position );
46  void setFrameOrientation( const Ogre::Quaternion& orientation );
47 
48  // Set the color and alpha of the visual, which are user-editable
49  // parameters and therefore don't come from the Point message.
50  void setColor( float r, float g, float b, float a );
51 
52  void setRadius( float r );
53 
54 private:
55  // The object implementing the point circle
57 
58  // A SceneNode whose pose is set to match the coordinate frame of
59  // the Point message header.
60  Ogre::SceneNode* frame_node_;
61 
62  // The SceneManager, kept here only so the destructor can ask it to
63  // destroy the ``frame_node_``.
64  Ogre::SceneManager* scene_manager_;
65 
66  float radius_;
67 
68 };
69 
70 } // end namespace rviz
71 
72 #endif // POINT_VISUAL_H
Ogre::SceneNode * frame_node_
Definition: point_visual.h:60
TFSIMD_FORCE_INLINE Vector3()
Ogre::SceneManager * scene_manager_
Definition: point_visual.h:64
r
static void getRainbowColor(float value, Ogre::ColourValue &color)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:51