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 <boost/bind.hpp>
00031
00032 #include <OGRE/OgreSceneNode.h>
00033 #include <OGRE/OgreSceneManager.h>
00034 #include <OGRE/OgreManualObject.h>
00035 #include <OGRE/OgreBillboardSet.h>
00036
00037 #include <tf/transform_listener.h>
00038
00039 #include "rviz/frame_manager.h"
00040 #include "rviz/ogre_helpers/arrow.h"
00041 #include "rviz/ogre_helpers/point_cloud.h"
00042 #include "rviz/properties/color_property.h"
00043 #include "rviz/properties/float_property.h"
00044 #include "rviz/properties/parse_color.h"
00045 #include "rviz/properties/ros_topic_property.h"
00046 #include "rviz/validate_floats.h"
00047 #include "rviz/display_context.h"
00048
00049 #include "grid_cells_display.h"
00050
00051 namespace rviz
00052 {
00053
00054 GridCellsDisplay::GridCellsDisplay()
00055 : Display()
00056 , messages_received_(0)
00057 , last_frame_count_( uint64_t( -1 ))
00058 {
00059 color_property_ = new ColorProperty( "Color", QColor( 25, 255, 0 ),
00060 "Color of the grid cells.", this );
00061
00062 alpha_property_ = new FloatProperty( "Alpha", 1.0,
00063 "Amount of transparency to apply to the cells.",
00064 this, SLOT( updateAlpha() ));
00065 alpha_property_->setMin( 0 );
00066 alpha_property_->setMax( 1 );
00067
00068 topic_property_ = new RosTopicProperty( "Topic", "",
00069 QString::fromStdString( ros::message_traits::datatype<nav_msgs::GridCells>() ),
00070 "nav_msgs::GridCells topic to subscribe to.",
00071 this, SLOT( updateTopic() ));
00072 }
00073
00074 void GridCellsDisplay::onInitialize()
00075 {
00076 tf_filter_ = new tf::MessageFilter<nav_msgs::GridCells>( *context_->getTFClient(), fixed_frame_.toStdString(),
00077 10, update_nh_ );
00078 static int count = 0;
00079 std::stringstream ss;
00080 ss << "PolyLine" << count++;
00081
00082 cloud_ = new PointCloud();
00083 cloud_->setRenderMode( PointCloud::RM_TILES );
00084 cloud_->setCommonDirection( Ogre::Vector3::UNIT_Z );
00085 cloud_->setCommonUpVector( Ogre::Vector3::UNIT_Y );
00086 scene_node_->attachObject( cloud_ );
00087 updateAlpha();
00088
00089 tf_filter_->connectInput( sub_ );
00090 tf_filter_->registerCallback( boost::bind( &GridCellsDisplay::incomingMessage, this, _1 ));
00091 context_->getFrameManager()->registerFilterForTransformStatusCheck( tf_filter_, this );
00092 }
00093
00094 GridCellsDisplay::~GridCellsDisplay()
00095 {
00096 unsubscribe();
00097 clear();
00098 scene_node_->detachObject( cloud_ );
00099 delete cloud_;
00100 delete tf_filter_;
00101 }
00102
00103 void GridCellsDisplay::clear()
00104 {
00105 cloud_->clear();
00106
00107 messages_received_ = 0;
00108 setStatus( StatusProperty::Warn, "Topic", "No messages received" );
00109 }
00110
00111 void GridCellsDisplay::updateTopic()
00112 {
00113 unsubscribe();
00114 subscribe();
00115 context_->queueRender();
00116 }
00117
00118 void GridCellsDisplay::updateAlpha()
00119 {
00120 cloud_->setAlpha( alpha_property_->getFloat() );
00121 context_->queueRender();
00122 }
00123
00124 void GridCellsDisplay::subscribe()
00125 {
00126 if ( !isEnabled() )
00127 {
00128 return;
00129 }
00130
00131 try
00132 {
00133 sub_.subscribe( update_nh_, topic_property_->getTopicStd(), 10 );
00134 setStatus( StatusProperty::Ok, "Topic", "OK" );
00135 }
00136 catch( ros::Exception& e )
00137 {
00138 setStatus( StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what() );
00139 }
00140 }
00141
00142 void GridCellsDisplay::unsubscribe()
00143 {
00144 sub_.unsubscribe();
00145 }
00146
00147 void GridCellsDisplay::onEnable()
00148 {
00149 subscribe();
00150 }
00151
00152 void GridCellsDisplay::onDisable()
00153 {
00154 unsubscribe();
00155 clear();
00156 }
00157
00158 void GridCellsDisplay::fixedFrameChanged()
00159 {
00160 clear();
00161
00162 tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
00163 }
00164
00165 bool validateFloats(const nav_msgs::GridCells& msg)
00166 {
00167 bool valid = true;
00168 valid = valid && validateFloats( msg.cell_width );
00169 valid = valid && validateFloats( msg.cell_height );
00170 valid = valid && validateFloats( msg.cells );
00171 return valid;
00172 }
00173
00174 void GridCellsDisplay::incomingMessage( const nav_msgs::GridCells::ConstPtr& msg )
00175 {
00176 if( !msg )
00177 {
00178 return;
00179 }
00180
00181 ++messages_received_;
00182
00183 if( context_->getFrameCount() == last_frame_count_ )
00184 {
00185 return;
00186 }
00187 last_frame_count_ = context_->getFrameCount();
00188
00189 cloud_->clear();
00190
00191 if( !validateFloats( *msg ))
00192 {
00193 setStatus( StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)" );
00194 return;
00195 }
00196
00197 setStatus( StatusProperty::Ok, "Topic", QString::number( messages_received_ ) + " messages received" );
00198
00199 Ogre::Vector3 position;
00200 Ogre::Quaternion orientation;
00201 if( !context_->getFrameManager()->getTransform( msg->header, position, orientation ))
00202 {
00203 ROS_DEBUG( "Error transforming from frame '%s' to frame '%s'",
00204 msg->header.frame_id.c_str(), qPrintable( fixed_frame_ ));
00205 }
00206
00207 scene_node_->setPosition( position );
00208 scene_node_->setOrientation( orientation );
00209
00210 if( msg->cell_width == 0 )
00211 {
00212 setStatus(StatusProperty::Error, "Topic", "Cell width is zero, cells will be invisible.");
00213 }
00214 else if( msg->cell_height == 0 )
00215 {
00216 setStatus(StatusProperty::Error, "Topic", "Cell height is zero, cells will be invisible.");
00217 }
00218
00219 cloud_->setDimensions(msg->cell_width, msg->cell_height, 0.0);
00220
00221 Ogre::ColourValue color_int = qtToOgre( color_property_->getColor() );
00222 uint32_t num_points = msg->cells.size();
00223
00224 typedef std::vector< PointCloud::Point > V_Point;
00225 V_Point points;
00226 points.resize( num_points );
00227 for(uint32_t i = 0; i < num_points; i++)
00228 {
00229 PointCloud::Point& current_point = points[ i ];
00230 current_point.position.x = msg->cells[i].x;
00231 current_point.position.y = msg->cells[i].y;
00232 current_point.position.z = msg->cells[i].z;
00233 current_point.color = color_int;
00234 }
00235
00236 cloud_->clear();
00237
00238 if ( !points.empty() )
00239 {
00240 cloud_->addPoints( &points.front(), points.size() );
00241 }
00242 }
00243
00244 void GridCellsDisplay::reset()
00245 {
00246 Display::reset();
00247 clear();
00248 }
00249
00250 }
00251
00252 #include <pluginlib/class_list_macros.h>
00253 PLUGINLIB_EXPORT_CLASS( rviz::GridCellsDisplay, rviz::Display )