$search
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 "interactive_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 00038 00039 #include <tf/transform_listener.h> 00040 00041 #include <OGRE/OgreSceneNode.h> 00042 #include <OGRE/OgreSceneManager.h> 00043 00044 namespace rviz 00045 { 00046 00048 bool validateFloats(const visualization_msgs::InteractiveMarker& msg) 00049 { 00050 bool valid = true; 00051 valid = valid && validateFloats(msg.pose); 00052 valid = valid && validateFloats(msg.scale); 00053 for ( unsigned c=0; c<msg.controls.size(); c++) 00054 { 00055 valid = valid && validateFloats( msg.controls[c].orientation ); 00056 for ( unsigned m=0; m<msg.controls[c].markers.size(); m++ ) 00057 { 00058 valid = valid && validateFloats(msg.controls[c].markers[m].pose); 00059 valid = valid && validateFloats(msg.controls[c].markers[m].scale); 00060 valid = valid && validateFloats(msg.controls[c].markers[m].color); 00061 valid = valid && validateFloats(msg.controls[c].markers[m].points); 00062 } 00063 } 00064 return valid; 00065 } 00067 00068 00069 00070 InteractiveMarkerDisplay::InteractiveMarkerDisplay( const std::string& name, VisualizationManager* manager ) 00071 : Display( name, manager ) 00072 , im_client_( this ) 00073 , tf_filter_(*manager->getTFClient(), "", 100, update_nh_) 00074 , tf_pose_filter_(*manager->getTFClient(), "", 100, update_nh_) 00075 , show_descriptions_(true) 00076 , show_tool_tips_(true) 00077 , show_axes_(false) 00078 { 00079 scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00080 00081 //message flow: incomingMarkerUpdate(..) -> tf_filter_ -> tfMarkerSuccess(..) -> message_queue_ -> update(..) 00082 00083 tf_filter_.registerCallback(boost::bind(&InteractiveMarkerDisplay::tfMarkerSuccess, this, _1)); 00084 tf_filter_.registerFailureCallback(boost::bind(&InteractiveMarkerDisplay::tfMarkerFail, this, _1, _2)); 00085 tf_pose_filter_.registerCallback(boost::bind(&InteractiveMarkerDisplay::tfPoseSuccess, this, _1)); 00086 tf_pose_filter_.registerFailureCallback(boost::bind(&InteractiveMarkerDisplay::tfPoseFail, this, _1, _2)); 00087 00088 client_id_ = ros::this_node::getName() + "/" + name; 00089 } 00090 00091 InteractiveMarkerDisplay::~InteractiveMarkerDisplay() 00092 { 00093 unsubscribe(); 00094 scene_manager_->destroySceneNode( scene_node_ ); 00095 } 00096 00097 void InteractiveMarkerDisplay::onEnable() 00098 { 00099 subscribe(); 00100 scene_node_->setVisible( true ); 00101 } 00102 00103 void InteractiveMarkerDisplay::onDisable() 00104 { 00105 unsubscribe(); 00106 tf_filter_.clear(); 00107 tf_pose_filter_.clear(); 00108 scene_node_->setVisible( false ); 00109 } 00110 00111 void InteractiveMarkerDisplay::setMarkerUpdateTopic(const std::string& topic) 00112 { 00113 if ( marker_update_topic_.empty() && topic.empty() ) 00114 { 00115 return; 00116 } 00117 unsubscribe(); 00118 marker_update_topic_ = topic; 00119 subscribe(); 00120 propertyChanged(marker_update_topic_property_); 00121 } 00122 00123 void InteractiveMarkerDisplay::subscribe() 00124 { 00125 if ( !isEnabled() ) 00126 { 00127 return; 00128 } 00129 00130 marker_update_sub_.shutdown(); 00131 num_publishers_ = 0; 00132 00133 try 00134 { 00135 if ( !marker_update_topic_.empty() ) 00136 { 00137 ROS_DEBUG( "Subscribing to %s", marker_update_topic_.c_str() ); 00138 marker_update_sub_ = update_nh_.subscribe(marker_update_topic_, 100, &InteractiveMarkerClient::processMarkerUpdate, &im_client_); 00139 } 00140 00141 setStatus(status_levels::Ok, "Topic", "OK"); 00142 } 00143 catch (ros::Exception& e) 00144 { 00145 setStatus(status_levels::Error, "Topic", std::string("Error subscribing: ") + e.what()); 00146 } 00147 00148 im_client_.clear(); 00149 } 00150 00151 bool InteractiveMarkerDisplay::subscribeToInit() 00152 { 00153 bool result = false; 00154 00155 ROS_DEBUG( "subscribeToInit()" ); 00156 try 00157 { 00158 if ( !marker_update_topic_.empty() ) 00159 { 00160 std::string init_topic = marker_update_topic_ + "_full"; 00161 ROS_DEBUG( "Subscribing to %s", init_topic.c_str() ); 00162 marker_init_sub_ = update_nh_.subscribe(init_topic, 100, &InteractiveMarkerClient::processMarkerInit, &im_client_); 00163 result = true; 00164 } 00165 00166 setStatus(status_levels::Ok, "InitTopic", "OK"); 00167 } 00168 catch (ros::Exception& e) 00169 { 00170 setStatus(status_levels::Error, "InitTopic", std::string("Error subscribing: ") + e.what()); 00171 } 00172 return result; 00173 } 00174 00175 void InteractiveMarkerDisplay::clearMarkers() 00176 { 00177 interactive_markers_.clear(); 00178 tf_filter_.clear(); 00179 tf_pose_filter_.clear(); 00180 } 00181 00182 void InteractiveMarkerDisplay::unsubscribe() 00183 { 00184 marker_update_sub_.shutdown(); 00185 marker_init_sub_.shutdown(); 00186 clearMarkers(); 00187 im_client_.unsubscribedFromInit(); 00188 } 00189 00190 void InteractiveMarkerDisplay::unsubscribeFromInit() 00191 { 00192 marker_init_sub_.shutdown(); 00193 } 00194 00195 void InteractiveMarkerDisplay::processMarkerChanges( const std::vector<visualization_msgs::InteractiveMarker>* markers, 00196 const std::vector<visualization_msgs::InteractiveMarkerPose>* poses, 00197 const std::vector<std::string>* erases ) 00198 { 00199 std::set<std::string> names; 00200 00201 if( markers != NULL ) 00202 { 00203 std::vector<visualization_msgs::InteractiveMarker>::const_iterator marker_it = markers->begin(); 00204 std::vector<visualization_msgs::InteractiveMarker>::const_iterator marker_end = markers->end(); 00205 for (; marker_it != marker_end; ++marker_it) 00206 { 00207 if ( !names.insert( marker_it->name ).second ) 00208 { 00209 setStatus(status_levels::Error, "Marker array", "The name '" + marker_it->name + "' was used multiple times."); 00210 } 00211 00212 visualization_msgs::InteractiveMarker::ConstPtr marker_ptr(new visualization_msgs::InteractiveMarker(*marker_it)); 00213 00214 if ( marker_it->header.stamp == ros::Time(0) ) 00215 { 00216 // bypass tf filter 00217 updateMarker( marker_ptr ); 00218 vis_manager_->queueRender(); 00219 } 00220 else 00221 { 00222 ROS_DEBUG("Forwarding %s to tf filter.", marker_it->name.c_str()); 00223 tf_filter_.add( marker_ptr ); 00224 } 00225 } 00226 } 00227 00228 if( poses != NULL ) 00229 { 00230 // pipe all pose updates into tf filter 00231 std::vector<visualization_msgs::InteractiveMarkerPose>::const_iterator pose_it = poses->begin(); 00232 std::vector<visualization_msgs::InteractiveMarkerPose>::const_iterator pose_end = poses->end(); 00233 00234 for (; pose_it != pose_end; ++pose_it) 00235 { 00236 if ( !names.insert( pose_it->name ).second ) 00237 { 00238 setStatus(status_levels::Error, "Marker array", "The name '" + pose_it->name + "' was used multiple times."); 00239 } 00240 00241 visualization_msgs::InteractiveMarkerPose::ConstPtr pose_ptr(new visualization_msgs::InteractiveMarkerPose(*pose_it)); 00242 00243 if ( pose_it->header.stamp == ros::Time(0) ) 00244 { 00245 updatePose( pose_ptr ); 00246 vis_manager_->queueRender(); 00247 } 00248 else 00249 { 00250 ROS_DEBUG("Forwarding pose for %s to tf filter.", pose_it->name.c_str()); 00251 tf_pose_filter_.add( pose_ptr ); 00252 } 00253 } 00254 } 00255 00256 if( erases != NULL ) 00257 { 00258 // erase markers 00259 std::vector<std::string>::const_iterator erase_it = erases->begin(); 00260 std::vector<std::string>::const_iterator erase_end = erases->end(); 00261 00262 for (; erase_it != erase_end; ++erase_it) 00263 { 00264 interactive_markers_.erase( *erase_it ); 00265 } 00266 } 00267 } 00268 00269 void InteractiveMarkerDisplay::tfMarkerSuccess( const visualization_msgs::InteractiveMarker::ConstPtr& marker ) 00270 { 00271 ROS_DEBUG("Queueing %s", marker->name.c_str()); 00272 boost::mutex::scoped_lock lock(queue_mutex_); 00273 marker_queue_.push_back(marker); 00274 vis_manager_->queueRender(); 00275 } 00276 00277 void InteractiveMarkerDisplay::tfMarkerFail(const visualization_msgs::InteractiveMarker::ConstPtr& marker, tf::FilterFailureReason reason) 00278 { 00279 std::string error = FrameManager::instance()->discoverFailureReason(marker->header.frame_id, marker->header.stamp, marker->__connection_header ? (*marker->__connection_header)["callerid"] : "unknown", reason); 00280 setStatus( status_levels::Error, marker->name, error); 00281 } 00282 00283 void InteractiveMarkerDisplay::tfPoseSuccess(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose) 00284 { 00285 ROS_DEBUG("Queueing pose for %s", marker_pose->name.c_str()); 00286 boost::mutex::scoped_lock lock(queue_mutex_); 00287 pose_queue_.push_back(marker_pose); 00288 vis_manager_->queueRender(); 00289 } 00290 00291 void InteractiveMarkerDisplay::tfPoseFail(const visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose, tf::FilterFailureReason reason) 00292 { 00293 std::string error = FrameManager::instance()->discoverFailureReason( 00294 marker_pose->header.frame_id, marker_pose->header.stamp, 00295 marker_pose->__connection_header ? (*marker_pose->__connection_header)["callerid"] : "unknown", reason); 00296 setStatus( status_levels::Error, marker_pose->name, error); 00297 } 00298 00299 00300 void InteractiveMarkerDisplay::update(float wall_dt, float ros_dt) 00301 { 00302 //detect if all servers have shut down 00303 if ( !im_client_.isPublisherListEmpty() ) 00304 { 00305 // weak detection of server shutdown 00306 unsigned num_pub = marker_update_sub_.getNumPublishers(); 00307 if ( num_pub < num_publishers_ ) 00308 { 00309 reset(); 00310 } 00311 else 00312 { 00313 num_publishers_ = num_pub; 00314 } 00315 00316 im_client_.flagLateConnections(); 00317 } 00318 00319 V_InteractiveMarkerMessage local_marker_queue; 00320 V_InteractiveMarkerPoseMessage local_pose_queue; 00321 00322 // the queue is accessed from another thread, so we need to lock it 00323 // and swap it's contents to a copy 00324 { 00325 boost::mutex::scoped_lock lock(queue_mutex_); 00326 local_marker_queue.swap( marker_queue_ ); 00327 local_pose_queue.swap( pose_queue_ ); 00328 } 00329 00330 if ( !local_marker_queue.empty() ) 00331 { 00332 V_InteractiveMarkerMessage::iterator message_it = local_marker_queue.begin(); 00333 V_InteractiveMarkerMessage::iterator message_end = local_marker_queue.end(); 00334 for ( ; message_it != message_end; ++message_it ) 00335 { 00336 updateMarker( *message_it ); 00337 } 00338 } 00339 00340 if ( !local_pose_queue.empty() ) 00341 { 00342 V_InteractiveMarkerPoseMessage::iterator message_it = local_pose_queue.begin(); 00343 V_InteractiveMarkerPoseMessage::iterator message_end = local_pose_queue.end(); 00344 for ( ; message_it != message_end; ++message_it ) 00345 { 00346 updatePose( *message_it ); 00347 } 00348 } 00349 00350 M_StringToInteractiveMarkerPtr::iterator it; 00351 for ( it = interactive_markers_.begin(); it != interactive_markers_.end(); it++ ) 00352 { 00353 it->second->update( wall_dt ); 00354 } 00355 } 00356 00357 void InteractiveMarkerDisplay::updateMarker( visualization_msgs::InteractiveMarker::ConstPtr& marker ) 00358 { 00359 if ( !validateFloats( *marker ) ) 00360 { 00361 setStatus( status_levels::Error, marker->name, "Message contains invalid floats!" ); 00362 return; 00363 } 00364 ROS_DEBUG("Processing interactive marker '%s'. %d", marker->name.c_str(), (int)marker->controls.size() ); 00365 00366 std::map< std::string, InteractiveMarkerPtr >::iterator int_marker_entry = interactive_markers_.find( marker->name ); 00367 00368 std::string topic = marker_update_topic_; 00369 00370 topic = ros::names::clean( topic ); 00371 topic = topic.substr( 0, topic.find_last_of( '/' ) ); 00372 00373 if ( int_marker_entry == interactive_markers_.end() ) 00374 { 00375 int_marker_entry = interactive_markers_.insert( std::make_pair(marker->name, InteractiveMarkerPtr ( new InteractiveMarker(this, vis_manager_, topic, client_id_) ) ) ).first; 00376 } 00377 00378 if ( int_marker_entry->second->processMessage( marker ) ) 00379 { 00380 int_marker_entry->second->setShowAxes(show_axes_); 00381 int_marker_entry->second->setShowDescription(show_descriptions_); 00382 } 00383 } 00384 00385 void InteractiveMarkerDisplay::updatePose( visualization_msgs::InteractiveMarkerPose::ConstPtr& marker_pose ) 00386 { 00387 if ( !validateFloats( marker_pose->pose ) ) 00388 { 00389 setStatus( status_levels::Error, marker_pose->name, "Pose message contains invalid floats!" ); 00390 return; 00391 } 00392 00393 std::map< std::string, InteractiveMarkerPtr >::iterator int_marker_entry = interactive_markers_.find( marker_pose->name ); 00394 00395 if ( int_marker_entry != interactive_markers_.end() ) 00396 { 00397 int_marker_entry->second->processMessage( marker_pose ); 00398 } 00399 } 00400 00401 void InteractiveMarkerDisplay::targetFrameChanged() 00402 { 00403 } 00404 00405 void InteractiveMarkerDisplay::fixedFrameChanged() 00406 { 00407 tf_filter_.setTargetFrame( fixed_frame_ ); 00408 tf_pose_filter_.setTargetFrame( fixed_frame_ ); 00409 reset(); 00410 } 00411 00412 void InteractiveMarkerDisplay::reset() 00413 { 00414 ROS_DEBUG("reset"); 00415 Display::reset(); 00416 unsubscribe(); 00417 subscribe(); 00418 } 00419 00420 void InteractiveMarkerDisplay::createProperties() 00421 { 00422 // interactive marker update topic 00423 marker_update_topic_property_ = property_manager_->createProperty<ROSTopicStringProperty>( 00424 "Update Topic", property_prefix_, boost::bind( &InteractiveMarkerDisplay::getMarkerUpdateTopic, this ), 00425 boost::bind( &InteractiveMarkerDisplay::setMarkerUpdateTopic, this, _1 ), parent_category_, this ); 00426 00427 setPropertyHelpText(marker_update_topic_property_, "visualization_msgs::InteractiveMarkerUpdate topic to subscribe to."); 00428 ROSTopicStringPropertyPtr marker_update_topic_property_locked = marker_update_topic_property_.lock(); 00429 marker_update_topic_property_locked->setMessageType(ros::message_traits::datatype<visualization_msgs::InteractiveMarkerUpdate>()); 00430 00431 // display options 00432 show_descriptions_property_ = property_manager_->createProperty<BoolProperty>( 00433 "Show Descriptions", property_prefix_, boost::bind( &InteractiveMarkerDisplay::getShowDescriptions, this ), 00434 boost::bind( &InteractiveMarkerDisplay::setShowDescriptions, this, _1 ), parent_category_, this ); 00435 00436 setPropertyHelpText(show_descriptions_property_, "Whether or not to show the descriptions of each Interactive Marker."); 00437 00438 show_tool_tips_property_ = property_manager_->createProperty<BoolProperty>( 00439 "Show Tool Tips", property_prefix_, boost::bind( &InteractiveMarkerDisplay::getShowToolTips, this ), 00440 boost::bind( &InteractiveMarkerDisplay::setShowToolTips, this, _1 ), parent_category_, this ); 00441 00442 setPropertyHelpText(show_tool_tips_property_, "Whether or not to show tool tips for the Interactive Marker Controls."); 00443 00444 show_axes_property_ = property_manager_->createProperty<BoolProperty>( 00445 "Show Axes", property_prefix_, boost::bind( &InteractiveMarkerDisplay::getShowAxes, this ), 00446 boost::bind( &InteractiveMarkerDisplay::setShowAxes, this, _1 ), parent_category_, this ); 00447 00448 setPropertyHelpText(show_axes_property_, "Whether or not to show the axes of each Interactive Marker."); 00449 } 00450 00451 00452 void InteractiveMarkerDisplay::setShowDescriptions( bool show ) 00453 { 00454 show_descriptions_ = show; 00455 00456 M_StringToInteractiveMarkerPtr::iterator it; 00457 for ( it = interactive_markers_.begin(); it != interactive_markers_.end(); it++ ) 00458 { 00459 it->second->setShowDescription(show); 00460 } 00461 00462 propertyChanged(show_descriptions_property_); 00463 } 00464 00465 00466 void InteractiveMarkerDisplay::setShowToolTips( bool show ) 00467 { 00468 show_tool_tips_ = show; 00469 00470 propertyChanged(show_descriptions_property_); 00471 } 00472 00473 00474 void InteractiveMarkerDisplay::setShowAxes( bool show ) 00475 { 00476 show_axes_ = show; 00477 00478 M_StringToInteractiveMarkerPtr::iterator it; 00479 for ( it = interactive_markers_.begin(); it != interactive_markers_.end(); it++ ) 00480 { 00481 it->second->setShowAxes(show); 00482 } 00483 00484 propertyChanged(show_axes_property_); 00485 } 00486 00487 void InteractiveMarkerDisplay::setStatusOk(const std::string& name, const std::string& text) 00488 { 00489 setStatus( status_levels::Ok, name, text ); 00490 } 00491 00492 void InteractiveMarkerDisplay::setStatusWarn(const std::string& name, const std::string& text) 00493 { 00494 setStatus( status_levels::Warn, name, text ); 00495 } 00496 00497 void InteractiveMarkerDisplay::setStatusError(const std::string& name, const std::string& text) 00498 { 00499 setStatus( status_levels::Error, name, text ); 00500 } 00501 00502 00503 } // namespace rviz