point_visual.cpp
Go to the documentation of this file.
1 #include <OgreVector3.h>
2 #include <OgreSceneNode.h>
3 #include <OgreSceneManager.h>
4 
6 
7 #include <ros/ros.h>
8 
9 #include "point_visual.h"
10 
11 namespace rviz
12 {
13 PointStampedVisual::PointStampedVisual(Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node)
14 {
15  scene_manager_ = scene_manager;
16 
17  // Ogre::SceneNode s form a tree, with each node storing the
18  // transform (position and orientation) of itself relative to its
19  // parent. Ogre does the math of combining those transforms when it
20  // is time to render.
21  //
22  // Here we create a node to store the pose of the Point's header frame
23  // relative to the RViz fixed frame.
24  frame_node_ = parent_node->createChildSceneNode();
25 
26  // We create the arrow object within the frame node so that we can
27  // set its position and direction relative to its header frame.
29 }
30 
32 {
33  // Delete the arrow to make it disappear.
34  delete point_;
35 
36  // Destroy the frame node since we don't need it anymore.
37  scene_manager_->destroySceneNode(frame_node_);
38 }
39 
40 
41 void PointStampedVisual::setMessage(const geometry_msgs::PointStamped::ConstPtr& msg)
42 {
43  Ogre::Vector3 scale(2 * radius_, 2 * radius_, 2 * radius_);
44  point_->setScale(scale);
45 
46  // Set the orientation of the arrow to match the direction of the
47  // acceleration vector.
48  Ogre::Vector3 point(msg->point.x, msg->point.y, msg->point.z);
49  point_->setPosition(point);
50 }
51 
52 // Position and orientation are passed through to the SceneNode.
53 void PointStampedVisual::setFramePosition(const Ogre::Vector3& position)
54 {
55  frame_node_->setPosition(position);
56 }
57 
58 void PointStampedVisual::setFrameOrientation(const Ogre::Quaternion& orientation)
59 {
60  frame_node_->setOrientation(orientation);
61 }
62 
63 // Color is passed through to the rviz object.
64 void PointStampedVisual::setColor(float r, float g, float b, float a)
65 {
66  point_->setColor(r, g, b, a);
67 }
68 
70 {
71  radius_ = r;
72 }
73 } // end namespace rviz
Ogre::SceneNode * frame_node_
Definition: point_visual.h:58
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
Definition: shape.cpp:160
void setColor(float r, float g, float b, float a) override
Set the color of the object. Values are in the range [0, 1].
Definition: shape.cpp:140
void setColor(float r, float g, float b, float a)
void setMessage(const geometry_msgs::PointStamped::ConstPtr &msg)
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Definition: shape.cpp:150
Ogre::SceneManager * scene_manager_
Definition: point_visual.h:62
PointStampedVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
void setFramePosition(const Ogre::Vector3 &position)
void setFrameOrientation(const Ogre::Quaternion &orientation)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:25