Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <OGRE/OgreManualObject.h>
00031 #include <OGRE/OgreSceneManager.h>
00032 #include <OGRE/OgreSceneNode.h>
00033
00034 #include "rviz/display_context.h"
00035 #include "rviz/frame_manager.h"
00036 #include "rviz/properties/color_property.h"
00037 #include "rviz/properties/float_property.h"
00038 #include "rviz/validate_floats.h"
00039
00040 #include "rviz/default_plugin/pose_array_display.h"
00041
00042 namespace rviz
00043 {
00044
00045 PoseArrayDisplay::PoseArrayDisplay()
00046 : manual_object_( NULL )
00047 {
00048 color_property_ = new ColorProperty( "Color", QColor( 255, 25, 0 ), "Color to draw the arrows.", this );
00049 length_property_ = new FloatProperty( "Arrow Length", 0.3, "Length of the arrows.", this );
00050 }
00051
00052 PoseArrayDisplay::~PoseArrayDisplay()
00053 {
00054 scene_manager_->destroyManualObject( manual_object_ );
00055 }
00056
00057 void PoseArrayDisplay::onInitialize()
00058 {
00059 MFDClass::onInitialize();
00060 manual_object_ = scene_manager_->createManualObject();
00061 manual_object_->setDynamic( true );
00062 scene_node_->attachObject( manual_object_ );
00063 }
00064
00065 bool validateFloats( const geometry_msgs::PoseArray& msg )
00066 {
00067 return validateFloats( msg.poses );
00068 }
00069
00070 void PoseArrayDisplay::processMessage( const geometry_msgs::PoseArray::ConstPtr& msg )
00071 {
00072 if( !validateFloats( *msg ))
00073 {
00074 setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
00075 return;
00076 }
00077
00078 manual_object_->clear();
00079
00080 Ogre::Vector3 position;
00081 Ogre::Quaternion orientation;
00082 if( !context_->getFrameManager()->getTransform( msg->header, position, orientation ))
00083 {
00084 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'", msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00085 }
00086
00087 scene_node_->setPosition( position );
00088 scene_node_->setOrientation( orientation );
00089
00090 manual_object_->clear();
00091
00092 Ogre::ColourValue color = color_property_->getOgreColor();
00093 float length = length_property_->getFloat();
00094 size_t num_poses = msg->poses.size();
00095 manual_object_->estimateVertexCount( num_poses * 6 );
00096 manual_object_->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_LIST );
00097 for( size_t i=0; i < num_poses; ++i )
00098 {
00099 Ogre::Vector3 pos( msg->poses[i].position.x,
00100 msg->poses[i].position.y,
00101 msg->poses[i].position.z );
00102 Ogre::Quaternion orient( msg->poses[i].orientation.w,
00103 msg->poses[i].orientation.x,
00104 msg->poses[i].orientation.y,
00105 msg->poses[i].orientation.z );
00106
00107
00108
00109 Ogre::Vector3 vertices[6];
00110 vertices[0] = pos;
00111 vertices[1] = pos + orient * Ogre::Vector3( length, 0, 0 );
00112 vertices[2] = vertices[ 1 ];
00113 vertices[3] = pos + orient * Ogre::Vector3( 0.75*length, 0.2*length, 0 );
00114 vertices[4] = vertices[ 1 ];
00115 vertices[5] = pos + orient * Ogre::Vector3( 0.75*length, -0.2*length, 0 );
00116
00117 for( int i = 0; i < 6; ++i )
00118 {
00119 manual_object_->position( vertices[i] );
00120 manual_object_->colour( color );
00121 }
00122 }
00123 manual_object_->end();
00124
00125 context_->queueRender();
00126 }
00127
00128 void PoseArrayDisplay::reset()
00129 {
00130 MFDClass::reset();
00131 if( manual_object_ )
00132 {
00133 manual_object_->clear();
00134 }
00135 }
00136
00137 }
00138
00139 #include <pluginlib/class_list_macros.h>
00140 PLUGINLIB_EXPORT_CLASS( rviz::PoseArrayDisplay, rviz::Display )