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/OgreSceneNode.h>
00031 #include <OGRE/OgreSceneManager.h>
00032 #include <OGRE/OgreManualObject.h>
00033 #include <OGRE/OgreBillboardSet.h>
00034
00035 #include "rviz/display_context.h"
00036 #include "rviz/frame_manager.h"
00037 #include "rviz/properties/color_property.h"
00038 #include "rviz/properties/float_property.h"
00039 #include "rviz/properties/parse_color.h"
00040 #include "rviz/validate_floats.h"
00041
00042 #include "polygon_display.h"
00043
00044 namespace rviz
00045 {
00046
00047 PolygonDisplay::PolygonDisplay()
00048 {
00049 color_property_ = new ColorProperty( "Color", QColor( 25, 255, 0 ),
00050 "Color to draw the polygon.", this, SLOT( queueRender() ));
00051 alpha_property_ = new FloatProperty( "Alpha", 1.0,
00052 "Amount of transparency to apply to the polygon.", this, SLOT( queueRender() ));
00053 alpha_property_->setMin( 0 );
00054 alpha_property_->setMax( 1 );
00055 }
00056
00057 PolygonDisplay::~PolygonDisplay()
00058 {
00059 scene_manager_->destroyManualObject( manual_object_ );
00060 }
00061
00062 void PolygonDisplay::onInitialize()
00063 {
00064 MFDClass::onInitialize();
00065
00066 manual_object_ = scene_manager_->createManualObject();
00067 manual_object_->setDynamic( true );
00068 scene_node_->attachObject( manual_object_ );
00069 }
00070
00071 void PolygonDisplay::reset()
00072 {
00073 MFDClass::reset();
00074 manual_object_->clear();
00075 }
00076
00077 bool validateFloats( const geometry_msgs::PolygonStamped& msg )
00078 {
00079 return validateFloats(msg.polygon.points);
00080 }
00081
00082 void PolygonDisplay::processMessage(const geometry_msgs::PolygonStamped::ConstPtr& msg)
00083 {
00084 if( !validateFloats( *msg ))
00085 {
00086 setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
00087 return;
00088 }
00089
00090 Ogre::Vector3 position;
00091 Ogre::Quaternion orientation;
00092 if( !context_->getFrameManager()->getTransform( msg->header, position, orientation ))
00093 {
00094 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00095 msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00096 }
00097
00098 scene_node_->setPosition( position );
00099 scene_node_->setOrientation( orientation );
00100
00101 manual_object_->clear();
00102
00103 Ogre::ColourValue color = qtToOgre( color_property_->getColor() );
00104 color.a = alpha_property_->getFloat();
00105
00106
00107
00108
00109
00110 uint32_t num_points = msg->polygon.points.size();
00111 if( num_points > 0 )
00112 {
00113 manual_object_->estimateVertexCount( num_points );
00114 manual_object_->begin( "BaseWhiteNoLighting", Ogre::RenderOperation::OT_LINE_STRIP );
00115 for( uint32_t i=0; i < num_points + 1; ++i )
00116 {
00117 const geometry_msgs::Point32& msg_point = msg->polygon.points[ i % num_points ];
00118 manual_object_->position( msg_point.x, msg_point.y, msg_point.z );
00119 manual_object_->colour( color );
00120 }
00121
00122 manual_object_->end();
00123 }
00124 }
00125
00126 }
00127
00128 #include <pluginlib/class_list_macros.h>
00129 PLUGINLIB_EXPORT_CLASS( rviz::PolygonDisplay, rviz::Display )