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 <sstream>
00031
00032 #include <tf/transform_listener.h>
00033
00034 #include "rviz/default_plugin/markers/arrow_marker.h"
00035 #include "rviz/default_plugin/markers/line_list_marker.h"
00036 #include "rviz/default_plugin/markers/line_strip_marker.h"
00037 #include "rviz/default_plugin/markers/mesh_resource_marker.h"
00038 #include "rviz/default_plugin/markers/points_marker.h"
00039 #include "rviz/default_plugin/markers/shape_marker.h"
00040 #include "rviz/default_plugin/markers/text_view_facing_marker.h"
00041 #include "rviz/default_plugin/markers/triangle_list_marker.h"
00042 #include "rviz/display_context.h"
00043 #include "rviz/frame_manager.h"
00044 #include "rviz/ogre_helpers/arrow.h"
00045 #include "rviz/ogre_helpers/billboard_line.h"
00046 #include "rviz/ogre_helpers/shape.h"
00047 #include "rviz/properties/int_property.h"
00048 #include "rviz/properties/property.h"
00049 #include "rviz/properties/ros_topic_property.h"
00050 #include "rviz/selection/selection_manager.h"
00051 #include "rviz/validate_floats.h"
00052
00053 #include "rviz/default_plugin/marker_display.h"
00054
00055 namespace rviz
00056 {
00057
00059
00060 MarkerDisplay::MarkerDisplay()
00061 : Display()
00062 {
00063 marker_topic_property_ = new RosTopicProperty( "Marker Topic", "visualization_marker",
00064 QString::fromStdString( ros::message_traits::datatype<visualization_msgs::Marker>() ),
00065 "visualization_msgs::Marker topic to subscribe to. <topic>_array will also"
00066 " automatically be subscribed with type visualization_msgs::MarkerArray.",
00067 this, SLOT( updateTopic() ));
00068
00069 queue_size_property_ = new IntProperty( "Queue Size", 100,
00070 "Advanced: set the size of the incoming Marker message queue. Increasing this is"
00071 " useful if your incoming TF data is delayed significantly from your Marker data, "
00072 "but it can greatly increase memory usage if the messages are big.",
00073 this, SLOT( updateQueueSize() ));
00074 queue_size_property_->setMin( 0 );
00075
00076 namespaces_category_ = new Property( "Namespaces", QVariant(), "", this );
00077 }
00078
00079 void MarkerDisplay::onInitialize()
00080 {
00081 tf_filter_ = new tf::MessageFilter<visualization_msgs::Marker>( *context_->getTFClient(),
00082 fixed_frame_.toStdString(),
00083 queue_size_property_->getInt(),
00084 update_nh_ );
00085
00086 tf_filter_->connectInput(sub_);
00087 tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, _1));
00088 tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, _1, _2));
00089 }
00090
00091 MarkerDisplay::~MarkerDisplay()
00092 {
00093 unsubscribe();
00094
00095 clearMarkers();
00096
00097 delete tf_filter_;
00098 }
00099
00100 void MarkerDisplay::clearMarkers()
00101 {
00102 markers_.clear();
00103 markers_with_expiration_.clear();
00104 frame_locked_markers_.clear();
00105 tf_filter_->clear();
00106 namespaces_category_->removeChildren();
00107 namespaces_.clear();
00108 }
00109
00110 void MarkerDisplay::onEnable()
00111 {
00112 subscribe();
00113 }
00114
00115 void MarkerDisplay::onDisable()
00116 {
00117 unsubscribe();
00118 tf_filter_->clear();
00119
00120 clearMarkers();
00121 }
00122
00123 void MarkerDisplay::updateQueueSize()
00124 {
00125 tf_filter_->setQueueSize( (uint32_t) queue_size_property_->getInt() );
00126 }
00127
00128 void MarkerDisplay::updateTopic()
00129 {
00130 unsubscribe();
00131 subscribe();
00132 }
00133
00134 void MarkerDisplay::subscribe()
00135 {
00136 if( !isEnabled() )
00137 {
00138 return;
00139 }
00140
00141 std::string marker_topic = marker_topic_property_->getTopicStd();
00142 if( !marker_topic.empty() )
00143 {
00144 array_sub_.shutdown();
00145 sub_.unsubscribe();
00146
00147 try
00148 {
00149 sub_.subscribe( update_nh_, marker_topic, queue_size_property_->getInt() );
00150 array_sub_ = update_nh_.subscribe( marker_topic + "_array", queue_size_property_->getInt(), &MarkerDisplay::incomingMarkerArray, this );
00151 setStatus( StatusProperty::Ok, "Topic", "OK" );
00152 }
00153 catch( ros::Exception& e )
00154 {
00155 setStatus( StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what() );
00156 }
00157 }
00158 }
00159
00160 void MarkerDisplay::unsubscribe()
00161 {
00162 sub_.unsubscribe();
00163 array_sub_.shutdown();
00164 }
00165
00166 void MarkerDisplay::deleteMarker(MarkerID id)
00167 {
00168 deleteMarkerStatus( id );
00169
00170 M_IDToMarker::iterator it = markers_.find( id );
00171 if( it != markers_.end() )
00172 {
00173 markers_with_expiration_.erase(it->second);
00174 frame_locked_markers_.erase(it->second);
00175 markers_.erase(it);
00176 }
00177 }
00178
00179 void MarkerDisplay::deleteMarkersInNamespace( const std::string& ns )
00180 {
00181 std::vector<MarkerID> to_delete;
00182
00183
00184 M_IDToMarker::iterator marker_it = markers_.begin();
00185 M_IDToMarker::iterator marker_end = markers_.end();
00186 for (; marker_it != marker_end; ++marker_it)
00187 {
00188 if (marker_it->first.first == ns)
00189 {
00190 to_delete.push_back(marker_it->first);
00191 }
00192 }
00193
00194 {
00195 std::vector<MarkerID>::iterator it = to_delete.begin();
00196 std::vector<MarkerID>::iterator end = to_delete.end();
00197 for (; it != end; ++it)
00198 {
00199 deleteMarker(*it);
00200 }
00201 }
00202 }
00203
00204 void MarkerDisplay::setMarkerStatus(MarkerID id, StatusLevel level, const std::string& text)
00205 {
00206 std::stringstream ss;
00207 ss << id.first << "/" << id.second;
00208 std::string marker_name = ss.str();
00209 setStatusStd(level, marker_name, text);
00210 }
00211
00212 void MarkerDisplay::deleteMarkerStatus(MarkerID id)
00213 {
00214 std::stringstream ss;
00215 ss << id.first << "/" << id.second;
00216 std::string marker_name = ss.str();
00217 deleteStatusStd(marker_name);
00218 }
00219
00220 void MarkerDisplay::incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr& array)
00221 {
00222 std::vector<visualization_msgs::Marker>::const_iterator it = array->markers.begin();
00223 std::vector<visualization_msgs::Marker>::const_iterator end = array->markers.end();
00224 for (; it != end; ++it)
00225 {
00226 const visualization_msgs::Marker& marker = *it;
00227 tf_filter_->add(visualization_msgs::Marker::Ptr(new visualization_msgs::Marker(marker)));
00228 }
00229 }
00230
00231 void MarkerDisplay::incomingMarker( const visualization_msgs::Marker::ConstPtr& marker )
00232 {
00233 boost::mutex::scoped_lock lock(queue_mutex_);
00234
00235 message_queue_.push_back(marker);
00236 }
00237
00238 void MarkerDisplay::failedMarker(const visualization_msgs::Marker::ConstPtr& marker, tf::FilterFailureReason reason)
00239 {
00240 std::string error = context_->getFrameManager()->discoverFailureReason(marker->header.frame_id, marker->header.stamp, marker->__connection_header ? (*marker->__connection_header)["callerid"] : "unknown", reason);
00241 setMarkerStatus(MarkerID(marker->ns, marker->id), StatusProperty::Error, error);
00242 }
00243
00244 bool validateFloats(const visualization_msgs::Marker& msg)
00245 {
00246 bool valid = true;
00247 valid = valid && validateFloats(msg.pose);
00248 valid = valid && validateFloats(msg.scale);
00249 valid = valid && validateFloats(msg.color);
00250 valid = valid && validateFloats(msg.points);
00251 return valid;
00252 }
00253
00254 void MarkerDisplay::processMessage( const visualization_msgs::Marker::ConstPtr& message )
00255 {
00256 if (!validateFloats(*message))
00257 {
00258 setMarkerStatus(MarkerID(message->ns, message->id), StatusProperty::Error, "Contains invalid floating point values (nans or infs)");
00259 return;
00260 }
00261
00262 switch ( message->action )
00263 {
00264 case visualization_msgs::Marker::ADD:
00265 processAdd( message );
00266 break;
00267
00268 case visualization_msgs::Marker::DELETE:
00269 processDelete( message );
00270 break;
00271
00272 default:
00273 ROS_ERROR( "Unknown marker action: %d\n", message->action );
00274 }
00275 }
00276
00277 void MarkerDisplay::processAdd( const visualization_msgs::Marker::ConstPtr& message )
00278 {
00279 QString namespace_name = QString::fromStdString( message->ns );
00280 M_Namespace::iterator ns_it = namespaces_.find( namespace_name );
00281 if( ns_it == namespaces_.end() )
00282 {
00283 ns_it = namespaces_.insert( namespace_name, new MarkerNamespace( namespace_name, namespaces_category_, this ));
00284 }
00285
00286 if( !ns_it.value()->isEnabled() )
00287 {
00288 return;
00289 }
00290
00291 deleteMarkerStatus( MarkerID( message->ns, message->id ));
00292
00293 bool create = true;
00294 MarkerBasePtr marker;
00295
00296 M_IDToMarker::iterator it = markers_.find( MarkerID(message->ns, message->id) );
00297 if ( it != markers_.end() )
00298 {
00299 marker = it->second;
00300 markers_with_expiration_.erase(marker);
00301 if ( message->type == marker->getMessage()->type )
00302 {
00303 create = false;
00304 }
00305 else
00306 {
00307 markers_.erase( it );
00308 }
00309 }
00310
00311 if ( create )
00312 {
00313 switch ( message->type )
00314 {
00315 case visualization_msgs::Marker::CUBE:
00316 case visualization_msgs::Marker::CYLINDER:
00317 case visualization_msgs::Marker::SPHERE:
00318 {
00319 marker.reset(new ShapeMarker(this, context_, scene_node_));
00320 }
00321 break;
00322
00323 case visualization_msgs::Marker::ARROW:
00324 {
00325 marker.reset(new ArrowMarker(this, context_, scene_node_));
00326 }
00327 break;
00328
00329 case visualization_msgs::Marker::LINE_STRIP:
00330 {
00331 marker.reset(new LineStripMarker(this, context_, scene_node_));
00332 }
00333 break;
00334 case visualization_msgs::Marker::LINE_LIST:
00335 {
00336 marker.reset(new LineListMarker(this, context_, scene_node_));
00337 }
00338 break;
00339 case visualization_msgs::Marker::SPHERE_LIST:
00340 case visualization_msgs::Marker::CUBE_LIST:
00341 case visualization_msgs::Marker::POINTS:
00342 {
00343 marker.reset(new PointsMarker(this, context_, scene_node_));
00344 }
00345 break;
00346 case visualization_msgs::Marker::TEXT_VIEW_FACING:
00347 {
00348 marker.reset(new TextViewFacingMarker(this, context_, scene_node_));
00349 }
00350 break;
00351 case visualization_msgs::Marker::MESH_RESOURCE:
00352 {
00353 marker.reset(new MeshResourceMarker(this, context_, scene_node_));
00354 }
00355 break;
00356
00357 case visualization_msgs::Marker::TRIANGLE_LIST:
00358 {
00359 marker.reset(new TriangleListMarker(this, context_, scene_node_));
00360 }
00361 break;
00362 default:
00363 ROS_ERROR( "Unknown marker type: %d", message->type );
00364 }
00365
00366 markers_.insert(std::make_pair(MarkerID(message->ns, message->id), marker));
00367 }
00368
00369 if (marker)
00370 {
00371 marker->setMessage(message);
00372
00373 if (message->lifetime.toSec() > 0.0001f)
00374 {
00375 markers_with_expiration_.insert(marker);
00376 }
00377
00378 if (message->frame_locked)
00379 {
00380 frame_locked_markers_.insert(marker);
00381 }
00382
00383 context_->queueRender();
00384 }
00385 }
00386
00387 void MarkerDisplay::processDelete( const visualization_msgs::Marker::ConstPtr& message )
00388 {
00389 deleteMarker(MarkerID(message->ns, message->id));
00390 context_->queueRender();
00391 }
00392
00393 void MarkerDisplay::update(float wall_dt, float ros_dt)
00394 {
00395 V_MarkerMessage local_queue;
00396
00397 {
00398 boost::mutex::scoped_lock lock(queue_mutex_);
00399
00400 local_queue.swap( message_queue_ );
00401 }
00402
00403 if ( !local_queue.empty() )
00404 {
00405 V_MarkerMessage::iterator message_it = local_queue.begin();
00406 V_MarkerMessage::iterator message_end = local_queue.end();
00407 for ( ; message_it != message_end; ++message_it )
00408 {
00409 visualization_msgs::Marker::ConstPtr& marker = *message_it;
00410
00411 processMessage( marker );
00412 }
00413 }
00414
00415 {
00416 S_MarkerBase::iterator it = markers_with_expiration_.begin();
00417 S_MarkerBase::iterator end = markers_with_expiration_.end();
00418 for (; it != end;)
00419 {
00420 MarkerBasePtr marker = *it;
00421 if (marker->expired())
00422 {
00423 ++it;
00424 deleteMarker(marker->getID());
00425 }
00426 else
00427 {
00428 ++it;
00429 }
00430 }
00431 }
00432
00433 {
00434 S_MarkerBase::iterator it = frame_locked_markers_.begin();
00435 S_MarkerBase::iterator end = frame_locked_markers_.end();
00436 for (; it != end; ++it)
00437 {
00438 MarkerBasePtr marker = *it;
00439 marker->updateFrameLocked();
00440 }
00441 }
00442 }
00443
00444 void MarkerDisplay::fixedFrameChanged()
00445 {
00446 tf_filter_->setTargetFrame( fixed_frame_.toStdString() );
00447
00448 clearMarkers();
00449 }
00450
00451 void MarkerDisplay::reset()
00452 {
00453 Display::reset();
00454 clearMarkers();
00455 }
00456
00458
00459
00460 MarkerNamespace::MarkerNamespace( const QString& name, Property* parent_property, MarkerDisplay* owner )
00461 : BoolProperty( name, true,
00462 "Enable/disable all markers in this namespace.",
00463 parent_property )
00464 , owner_( owner )
00465 {
00466
00467
00468
00469 connect( this, SIGNAL( changed() ), this, SLOT( onEnableChanged() ));
00470 }
00471
00472 void MarkerNamespace::onEnableChanged()
00473 {
00474 if( !isEnabled() )
00475 {
00476 owner_->deleteMarkersInNamespace( getName().toStdString() );
00477 }
00478 }
00479
00480 }
00481
00482 #include <pluginlib/class_list_macros.h>
00483 PLUGINLIB_EXPORT_CLASS( rviz::MarkerDisplay, rviz::Display )