point_visual.cpp
Go to the documentation of this file.
00001 #include <OgreVector3.h>
00002 #include <OgreSceneNode.h>
00003 #include <OgreSceneManager.h>
00004 
00005 #include <rviz/ogre_helpers/shape.h>
00006 
00007 #include <ros/ros.h>
00008 
00009 #include "point_visual.h"
00010 
00011 namespace rviz
00012 {
00013 
00014     PointStampedVisual::PointStampedVisual( Ogre::SceneManager* scene_manager, Ogre::SceneNode* parent_node )
00015     {
00016         scene_manager_ = scene_manager;
00017 
00018         // Ogre::SceneNode s form a tree, with each node storing the
00019         // transform (position and orientation) of itself relative to its
00020         // parent.  Ogre does the math of combining those transforms when it
00021         // is time to render.
00022         //
00023         // Here we create a node to store the pose of the Point's header frame
00024         // relative to the RViz fixed frame.
00025         frame_node_ = parent_node->createChildSceneNode();
00026 
00027         // We create the arrow object within the frame node so that we can
00028         // set its position and direction relative to its header frame.
00029         point_ = new rviz::Shape( rviz::Shape::Sphere, scene_manager_, frame_node_ );
00030     }
00031 
00032     PointStampedVisual::~PointStampedVisual()
00033     {
00034         // Delete the arrow to make it disappear.
00035         delete point_;
00036 
00037         // Destroy the frame node since we don't need it anymore.
00038         scene_manager_->destroySceneNode( frame_node_ );
00039     }
00040 
00041 
00042 void PointStampedVisual::setMessage( const geometry_msgs::PointStamped::ConstPtr& msg )
00043     {
00044         Ogre::Vector3 scale( radius_, radius_, radius_ );
00045         point_->setScale( scale );
00046 
00047         // Set the orientation of the arrow to match the direction of the
00048         // acceleration vector.
00049         Ogre::Vector3 point( msg->point.x, msg->point.y, msg->point.z);
00050         point_->setPosition( point );
00051     }
00052 
00053     // Position and orientation are passed through to the SceneNode.
00054     void PointStampedVisual::setFramePosition( const Ogre::Vector3& position )
00055     {
00056         frame_node_->setPosition( position );
00057     }
00058 
00059     void PointStampedVisual::setFrameOrientation( const Ogre::Quaternion& orientation )
00060     {
00061         frame_node_->setOrientation( orientation );
00062     }
00063 
00064     // Color is passed through to the rviz object.
00065     void PointStampedVisual::setColor( float r, float g, float b, float a )
00066     {
00067         point_->setColor( r, g, b, a );
00068     }
00069 
00070     void PointStampedVisual::setRadius( float r )
00071     {
00072         radius_ = r;
00073     }
00074 } // end namespace rviz
00075 


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Thu Jun 6 2019 18:02:15