marker_display.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "marker_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/properties/property_manager.h"
00033 #include "rviz/properties/property.h"
00034 #include "rviz/selection/selection_manager.h"
00035 #include "rviz/frame_manager.h"
00036 #include "rviz/validate_floats.h"
00037 #include "rviz/uniform_string_stream.h"
00038 
00039 #include "markers/shape_marker.h"
00040 #include "markers/arrow_marker.h"
00041 #include "markers/line_list_marker.h"
00042 #include "markers/line_strip_marker.h"
00043 #include "markers/points_marker.h"
00044 #include "markers/text_view_facing_marker.h"
00045 #include "markers/mesh_resource_marker.h"
00046 #include "markers/triangle_list_marker.h"
00047 
00048 #include <rviz/ogre_helpers/arrow.h>
00049 #include <rviz/ogre_helpers/shape.h>
00050 #include <rviz/ogre_helpers/billboard_line.h>
00051 
00052 #include <tf/transform_listener.h>
00053 
00054 #include <OGRE/OgreSceneNode.h>
00055 #include <OGRE/OgreSceneManager.h>
00056 
00057 namespace rviz
00058 {
00059 
00063 
00064 MarkerDisplay::MarkerDisplay()
00065   : Display()
00066   , marker_topic_("visualization_marker")
00067   , hidden_ (false)
00068 {
00069 }
00070 
00071 void MarkerDisplay::onInitialize()
00072 {
00073   tf_filter_ = new tf::MessageFilter<visualization_msgs::Marker>(*vis_manager_->getTFClient(), "", 100, update_nh_);
00074   scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00075 
00076   tf_filter_->connectInput(sub_);
00077   tf_filter_->registerCallback(boost::bind(&MarkerDisplay::incomingMarker, this, _1));
00078   tf_filter_->registerFailureCallback(boost::bind(&MarkerDisplay::failedMarker, this, _1, _2));
00079 }
00080 
00081 MarkerDisplay::~MarkerDisplay()
00082 {
00083   unsubscribe();
00084 
00085   clearMarkers();
00086 
00087   delete tf_filter_;
00088 }
00089 
00090 MarkerBasePtr MarkerDisplay::getMarker(MarkerID id)
00091 {
00092   M_IDToMarker::iterator it = markers_.find(id);
00093   if (it != markers_.end())
00094   {
00095     return it->second;
00096   }
00097 
00098   return MarkerBasePtr();
00099 }
00100 
00101 void MarkerDisplay::clearMarkers()
00102 {
00103   markers_.clear();
00104   markers_with_expiration_.clear();
00105   frame_locked_markers_.clear();
00106   tf_filter_->clear();
00107 
00108   if (property_manager_)
00109   {
00110     M_Namespace::iterator it = namespaces_.begin();
00111     M_Namespace::iterator end = namespaces_.end();
00112     for (; it != end; ++it)
00113     {
00114       property_manager_->deleteProperty(it->second.prop.lock());
00115     }
00116   }
00117 
00118   namespaces_.clear();
00119 }
00120 
00121 void MarkerDisplay::onEnable()
00122 {
00123   subscribe();
00124   scene_node_->setVisible( enabled_ && !hidden_ );
00125 }
00126 
00127 void MarkerDisplay::onDisable()
00128 {
00129   unsubscribe();
00130   tf_filter_->clear();
00131   clearMarkers();
00132   scene_node_->setVisible( enabled_ && !hidden_ );
00133 }
00134 
00135 void MarkerDisplay::hideVisible()
00136 {
00137   hidden_ = true;
00138   scene_node_->setVisible( enabled_ && !hidden_ );
00139 }
00140 
00141 void MarkerDisplay::restoreVisible()
00142 {
00143   hidden_ = false;
00144   scene_node_->setVisible( enabled_ && !hidden_ );
00145 }
00146 
00147 void MarkerDisplay::setQueueSize( int size )
00148 {
00149   if( size != (int) tf_filter_->getQueueSize() )
00150   {
00151     tf_filter_->setQueueSize( (uint32_t) size );
00152     propertyChanged( queue_size_property_ );
00153   }
00154 }
00155 
00156 int MarkerDisplay::getQueueSize()
00157 {
00158   return (int) tf_filter_->getQueueSize();
00159 }
00160 
00161 void MarkerDisplay::setMarkerTopic(const std::string& topic)
00162 {
00163   unsubscribe();
00164   marker_topic_ = topic;
00165   subscribe();
00166 
00167   propertyChanged(marker_topic_property_);
00168 }
00169 
00170 void MarkerDisplay::subscribe()
00171 {
00172   if ( !isEnabled() )
00173   {
00174     return;
00175   }
00176 
00177   if (!marker_topic_.empty())
00178   {
00179     array_sub_.shutdown();
00180     sub_.unsubscribe();
00181 
00182     try
00183     {
00184       sub_.subscribe(update_nh_, marker_topic_, 1000);
00185       array_sub_ = update_nh_.subscribe(marker_topic_ + "_array", 1000, &MarkerDisplay::incomingMarkerArray, this);
00186       setStatus(status_levels::Ok, "Topic", "OK");
00187     }
00188     catch (ros::Exception& e)
00189     {
00190       setStatus(status_levels::Error, "Topic", std::string("Error subscribing: ") + e.what());
00191     }
00192   }
00193 }
00194 
00195 void MarkerDisplay::unsubscribe()
00196 {
00197   sub_.unsubscribe();
00198   array_sub_.shutdown();
00199 }
00200 
00201 void MarkerDisplay::deleteMarker(MarkerID id)
00202 {
00203   deleteMarkerStatus(id);
00204 
00205   M_IDToMarker::iterator it = markers_.find(id);
00206   if (it != markers_.end())
00207   {
00208     markers_with_expiration_.erase(it->second);
00209     frame_locked_markers_.erase(it->second);
00210     markers_.erase(it);
00211   }
00212 }
00213 
00214 void MarkerDisplay::setNamespaceEnabled(const std::string& ns, bool enabled)
00215 {
00216   M_Namespace::iterator it = namespaces_.find(ns);
00217   if (it != namespaces_.end())
00218   {
00219     it->second.enabled = enabled;
00220 
00221     std::vector<MarkerID> to_delete;
00222 
00223     // TODO: this is inefficient, should store every in-use id per namespace and lookup by that
00224     M_IDToMarker::iterator marker_it = markers_.begin();
00225     M_IDToMarker::iterator marker_end = markers_.end();
00226     for (; marker_it != marker_end; ++marker_it)
00227     {
00228       if (marker_it->first.first == ns)
00229       {
00230         to_delete.push_back(marker_it->first);
00231       }
00232     }
00233 
00234     {
00235       std::vector<MarkerID>::iterator it = to_delete.begin();
00236       std::vector<MarkerID>::iterator end = to_delete.end();
00237       for (; it != end; ++it)
00238       {
00239         deleteMarker(*it);
00240       }
00241     }
00242   }
00243 }
00244 
00245 bool MarkerDisplay::isNamespaceEnabled(const std::string& ns)
00246 {
00247   M_Namespace::iterator it = namespaces_.find(ns);
00248   if (it != namespaces_.end())
00249   {
00250     return it->second.enabled;
00251   }
00252 
00253   return true;
00254 }
00255 
00256 void MarkerDisplay::setMarkerStatus(MarkerID id, StatusLevel level, const std::string& text)
00257 {
00258   UniformStringStream ss;
00259   ss << id.first << "/" << id.second;
00260   std::string marker_name = ss.str();
00261   setStatus(level, marker_name, text);
00262 }
00263 
00264 void MarkerDisplay::deleteMarkerStatus(MarkerID id)
00265 {
00266   UniformStringStream ss;
00267   ss << id.first << "/" << id.second;
00268   std::string marker_name = ss.str();
00269   deleteStatus(marker_name);
00270 }
00271 
00272 void MarkerDisplay::incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr& array)
00273 {
00274   std::vector<visualization_msgs::Marker>::const_iterator it = array->markers.begin();
00275   std::vector<visualization_msgs::Marker>::const_iterator end = array->markers.end();
00276   for (; it != end; ++it)
00277   {
00278     const visualization_msgs::Marker& marker = *it;
00279     tf_filter_->add(visualization_msgs::Marker::Ptr(new visualization_msgs::Marker(marker)));
00280   }
00281 }
00282 
00283 void MarkerDisplay::incomingMarker( const visualization_msgs::Marker::ConstPtr& marker )
00284 {
00285   boost::mutex::scoped_lock lock(queue_mutex_);
00286 
00287   message_queue_.push_back(marker);
00288 }
00289 
00290 void MarkerDisplay::failedMarker(const visualization_msgs::Marker::ConstPtr& marker, tf::FilterFailureReason reason)
00291 {
00292   std::string error = FrameManager::instance()->discoverFailureReason(marker->header.frame_id, marker->header.stamp, marker->__connection_header ? (*marker->__connection_header)["callerid"] : "unknown", reason);
00293   setMarkerStatus(MarkerID(marker->ns, marker->id), status_levels::Error, error);
00294 }
00295 
00296 bool validateFloats(const visualization_msgs::Marker& msg)
00297 {
00298   bool valid = true;
00299   valid = valid && validateFloats(msg.pose);
00300   valid = valid && validateFloats(msg.scale);
00301   valid = valid && validateFloats(msg.color);
00302   valid = valid && validateFloats(msg.points);
00303   return valid;
00304 }
00305 
00306 void MarkerDisplay::processMessage( const visualization_msgs::Marker::ConstPtr& message )
00307 {
00308   if (!validateFloats(*message))
00309   {
00310     setMarkerStatus(MarkerID(message->ns, message->id), status_levels::Error, "Contains invalid floating point values (nans or infs)");
00311     return;
00312   }
00313 
00314   switch ( message->action )
00315   {
00316   case visualization_msgs::Marker::ADD:
00317     processAdd( message );
00318     break;
00319 
00320   case visualization_msgs::Marker::DELETE:
00321     processDelete( message );
00322     break;
00323 
00324   default:
00325     ROS_ERROR( "Unknown marker action: %d\n", message->action );
00326   }
00327 }
00328 
00329 void MarkerDisplay::processAdd( const visualization_msgs::Marker::ConstPtr& message )
00330 {
00331   //
00332   M_Namespace::iterator ns_it = namespaces_.find(message->ns);
00333   if (ns_it == namespaces_.end())
00334   {
00335     Namespace ns;
00336     ns.name = message->ns;
00337     ns.enabled = true;
00338 
00339     if (property_manager_)
00340     {
00341       ns.prop = property_manager_->createProperty<BoolProperty>(ns.name, property_prefix_, boost::bind(&MarkerDisplay::isNamespaceEnabled, this, ns.name),
00342                                                                               boost::bind(&MarkerDisplay::setNamespaceEnabled, this, ns.name, _1), namespaces_category_, this);
00343       setPropertyHelpText(ns.prop, "Enable/disable all markers in this namespace.");
00344     }
00345 
00346     ns_it = namespaces_.insert(std::make_pair(ns.name, ns)).first;
00347   }
00348 
00349   if (!ns_it->second.enabled)
00350   {
00351     return;
00352   }
00353 
00354   deleteMarkerStatus(MarkerID(message->ns, message->id));
00355 
00356   bool create = true;
00357   MarkerBasePtr marker;
00358 
00359   M_IDToMarker::iterator it = markers_.find( MarkerID(message->ns, message->id) );
00360   if ( it != markers_.end() )
00361   {
00362     marker = it->second;
00363     markers_with_expiration_.erase(marker);
00364     if ( message->type == marker->getMessage()->type )
00365     {
00366       create = false;
00367     }
00368     else
00369     {
00370       markers_.erase( it );
00371     }
00372   }
00373 
00374   if ( create )
00375   {
00376     switch ( message->type )
00377     {
00378     case visualization_msgs::Marker::CUBE:
00379     case visualization_msgs::Marker::CYLINDER:
00380     case visualization_msgs::Marker::SPHERE:
00381       {
00382         marker.reset(new ShapeMarker(this, vis_manager_, scene_node_));
00383       }
00384       break;
00385 
00386     case visualization_msgs::Marker::ARROW:
00387       {
00388         marker.reset(new ArrowMarker(this, vis_manager_, scene_node_));
00389       }
00390       break;
00391 
00392     case visualization_msgs::Marker::LINE_STRIP:
00393       {
00394         marker.reset(new LineStripMarker(this, vis_manager_, scene_node_));
00395       }
00396       break;
00397     case visualization_msgs::Marker::LINE_LIST:
00398       {
00399         marker.reset(new LineListMarker(this, vis_manager_, scene_node_));
00400       }
00401       break;
00402     case visualization_msgs::Marker::SPHERE_LIST:
00403     case visualization_msgs::Marker::CUBE_LIST:
00404     case visualization_msgs::Marker::POINTS:
00405       {
00406         marker.reset(new PointsMarker(this, vis_manager_, scene_node_));
00407       }
00408       break;
00409     case visualization_msgs::Marker::TEXT_VIEW_FACING:
00410       {
00411         marker.reset(new TextViewFacingMarker(this, vis_manager_, scene_node_));
00412       }
00413       break;
00414     case visualization_msgs::Marker::MESH_RESOURCE:
00415       {
00416         marker.reset(new MeshResourceMarker(this, vis_manager_, scene_node_));
00417       }
00418       break;
00419 
00420     case visualization_msgs::Marker::TRIANGLE_LIST:
00421     {
00422       marker.reset(new TriangleListMarker(this, vis_manager_, scene_node_));
00423     }
00424     break;
00425     default:
00426       ROS_ERROR( "Unknown marker type: %d", message->type );
00427     }
00428 
00429     markers_.insert(std::make_pair(MarkerID(message->ns, message->id), marker));
00430   }
00431 
00432   if (marker)
00433   {
00434     marker->setMessage(message);
00435 
00436     if (message->lifetime.toSec() > 0.0001f)
00437     {
00438       markers_with_expiration_.insert(marker);
00439     }
00440 
00441     if (message->frame_locked)
00442     {
00443       frame_locked_markers_.insert(marker);
00444     }
00445 
00446     causeRender();
00447   }
00448 }
00449 
00450 void MarkerDisplay::processDelete( const visualization_msgs::Marker::ConstPtr& message )
00451 {
00452   deleteMarker(MarkerID(message->ns, message->id));
00453   causeRender();
00454 }
00455 
00456 void MarkerDisplay::update(float wall_dt, float ros_dt)
00457 {
00458   V_MarkerMessage local_queue;
00459 
00460   {
00461     boost::mutex::scoped_lock lock(queue_mutex_);
00462 
00463     local_queue.swap( message_queue_ );
00464   }
00465 
00466   if ( !local_queue.empty() )
00467   {
00468     V_MarkerMessage::iterator message_it = local_queue.begin();
00469     V_MarkerMessage::iterator message_end = local_queue.end();
00470     for ( ; message_it != message_end; ++message_it )
00471     {
00472       visualization_msgs::Marker::ConstPtr& marker = *message_it;
00473 
00474       processMessage( marker );
00475     }
00476   }
00477 
00478   {
00479     S_MarkerBase::iterator it = markers_with_expiration_.begin();
00480     S_MarkerBase::iterator end = markers_with_expiration_.end();
00481     for (; it != end;)
00482     {
00483       MarkerBasePtr marker = *it;
00484       if (marker->expired())
00485       {
00486         S_MarkerBase::iterator copy = it;
00487         ++it;
00488         deleteMarker(marker->getID());
00489       }
00490       else
00491       {
00492         ++it;
00493       }
00494     }
00495   }
00496 
00497   {
00498     S_MarkerBase::iterator it = frame_locked_markers_.begin();
00499     S_MarkerBase::iterator end = frame_locked_markers_.end();
00500     for (; it != end; ++it)
00501     {
00502       MarkerBasePtr marker = *it;
00503       marker->updateFrameLocked();
00504     }
00505   }
00506 }
00507 
00508 void MarkerDisplay::fixedFrameChanged()
00509 {
00510   tf_filter_->setTargetFrame( fixed_frame_ );
00511 
00512   clearMarkers();
00513 }
00514 
00515 void MarkerDisplay::reset()
00516 {
00517   Display::reset();
00518   clearMarkers();
00519 }
00520 
00521 void MarkerDisplay::createProperties()
00522 {
00523   marker_topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( "Marker Topic", property_prefix_, boost::bind( &MarkerDisplay::getMarkerTopic, this ),
00524                                                                                 boost::bind( &MarkerDisplay::setMarkerTopic, this, _1 ), parent_category_, this );
00525   setPropertyHelpText(marker_topic_property_, "visualization_msgs::Marker topic to subscribe to.  <topic>_array will also automatically be subscribed with type visualization_msgs::MarkerArray.");
00526   ROSTopicStringPropertyPtr topic_prop = marker_topic_property_.lock();
00527   topic_prop->setMessageType(ros::message_traits::datatype<visualization_msgs::Marker>());
00528 
00529   queue_size_property_ = property_manager_->createProperty<IntProperty>( "Queue Size", property_prefix_,
00530                                                                          boost::bind( &MarkerDisplay::getQueueSize, this ),
00531                                                                          boost::bind( &MarkerDisplay::setQueueSize, this, _1 ),
00532                                                                          parent_category_, this );
00533   setPropertyHelpText( queue_size_property_, "Advanced: set the size of the incoming Marker message queue.  Increasing this is useful if your incoming TF data is delayed significantly from your Marker data, but it can greatly increase memory usage if the messages are big." );
00534 
00535   namespaces_category_ = property_manager_->createCategory("Namespaces", property_prefix_, parent_category_, this);
00536 }
00537 
00538 } // namespace rviz


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32