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


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53