34 #include <visualization_msgs/InteractiveMarkerInit.h>
36 #include <boost/bind.hpp>
52 if (!server_id.empty())
61 std::string update_topic = topic_ns +
"/update";
62 std::string init_topic = update_topic +
"_full";
63 std::string feedback_topic = topic_ns +
"/feedback";
112 boost::recursive_mutex::scoped_lock lock(
mutex_ );
119 M_UpdateContext::iterator update_it;
121 visualization_msgs::InteractiveMarkerUpdate
update;
122 update.type = visualization_msgs::InteractiveMarkerUpdate::UPDATE;
130 M_MarkerContext::iterator marker_context_it =
marker_contexts_.find( update_it->first );
132 switch ( update_it->second.update_type )
138 ROS_DEBUG(
"Creating new context for %s", update_it->first.c_str());
142 marker_context_it->second.default_feedback_cb = update_it->second.default_feedback_cb;
143 marker_context_it->second.feedback_cbs = update_it->second.feedback_cbs;
146 marker_context_it->second.int_marker = update_it->second.int_marker;
148 update.markers.push_back( marker_context_it->second.int_marker );
156 ROS_ERROR(
"Pending pose update for non-existing marker found. This is a bug in InteractiveMarkerInterface." );
160 marker_context_it->second.int_marker.pose = update_it->second.int_marker.pose;
161 marker_context_it->second.int_marker.header = update_it->second.int_marker.header;
163 visualization_msgs::InteractiveMarkerPose pose_update;
164 pose_update.header = marker_context_it->second.int_marker.header;
165 pose_update.pose = marker_context_it->second.int_marker.pose;
166 pose_update.name = marker_context_it->second.int_marker.name;
167 update.poses.push_back( pose_update );
177 update.erases.push_back( update_it->first );
194 boost::recursive_mutex::scoped_lock lock(
mutex_ );
207 boost::recursive_mutex::scoped_lock lock(
mutex_ );
211 M_MarkerContext::iterator it;
233 boost::recursive_mutex::scoped_lock lock(
mutex_ );
235 M_MarkerContext::iterator marker_context_it =
marker_contexts_.find( name );
246 if (
header.frame_id.empty() )
250 doSetPose( update_it, name, pose, marker_context_it->second.int_marker.header );
254 doSetPose( update_it, name, pose, update_it->second.int_marker.header );
258 BOOST_ASSERT_MSG(
false,
"Marker does not exist and there is no pending creation.");
271 boost::recursive_mutex::scoped_lock lock(
mutex_ );
273 M_MarkerContext::iterator marker_context_it =
marker_contexts_.find( name );
289 marker_context_it->second.default_feedback_cb = feedback_cb;
295 marker_context_it->second.feedback_cbs[feedback_type] = feedback_cb;
299 marker_context_it->second.feedback_cbs.erase( feedback_type );
308 update_it->second.default_feedback_cb = feedback_cb;
314 update_it->second.feedback_cbs[feedback_type] = feedback_cb;
318 update_it->second.feedback_cbs.erase( feedback_type );
327 boost::recursive_mutex::scoped_lock lock(
mutex_ );
329 M_UpdateContext::iterator update_it =
pending_updates_.find( int_marker.name );
336 update_it->second.int_marker = int_marker;
344 setCallback( int_marker.name, feedback_cb, feedback_type );
349 boost::recursive_mutex::scoped_lock lock(
mutex_ );
355 M_MarkerContext::const_iterator marker_context_it =
marker_contexts_.find( name );
361 int_marker = marker_context_it->second.int_marker;
366 switch ( update_it->second.update_type )
373 M_MarkerContext::const_iterator marker_context_it =
marker_contexts_.find( name );
378 int_marker = marker_context_it->second.int_marker;
379 int_marker.pose = update_it->second.int_marker.pose;
384 int_marker = update_it->second.int_marker;
393 boost::recursive_mutex::scoped_lock lock(
mutex_ );
395 M_MarkerContext::iterator it;
396 std::vector<std::string> names;
399 names.push_back( it->first );
407 boost::recursive_mutex::scoped_lock lock(
mutex_ );
409 visualization_msgs::InteractiveMarkerInit
init;
414 M_MarkerContext::iterator it;
417 ROS_DEBUG(
"Publishing %s", it->second.int_marker.name.c_str() );
418 init.markers.push_back( it->second.int_marker );
426 boost::recursive_mutex::scoped_lock lock(
mutex_ );
428 M_MarkerContext::iterator marker_context_it =
marker_contexts_.find( feedback->marker_name );
442 ROS_DEBUG(
"Rejecting feedback for %s: conflicting feedback from separate clients.", feedback->marker_name.c_str() );
449 if ( feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE )
463 boost::unordered_map<uint8_t,FeedbackCallback>::iterator feedback_cb_it = marker_context.
feedback_cbs.find( feedback->event_type );
464 if ( feedback_cb_it != marker_context.
feedback_cbs.end() && feedback_cb_it->second )
467 feedback_cb_it->second( feedback );
479 visualization_msgs::InteractiveMarkerUpdate empty_update;
480 empty_update.type = visualization_msgs::InteractiveMarkerUpdate::KEEP_ALIVE;
505 update_it->second.int_marker.pose = pose;
506 update_it->second.int_marker.header =
header;
507 ROS_DEBUG(
"Marker '%s' is now at %f, %f, %f", update_it->first.c_str(), pose.position.x, pose.position.y, pose.position.z );