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


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