interactive_marker_server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: David Gossow
30  */
31 
33 
34 #include <visualization_msgs/InteractiveMarkerInit.h>
35 
36 #include <boost/bind.hpp>
37 #include <boost/make_shared.hpp>
38 
39 namespace interactive_markers
40 {
41 
42 InteractiveMarkerServer::InteractiveMarkerServer( const std::string &topic_ns, const std::string &server_id, bool spin_thread ) :
43  topic_ns_(topic_ns),
44  seq_num_(0)
45 {
46  if ( spin_thread )
47  {
48  // if we're spinning our own thread, we'll also need our own callback queue
50  }
51 
52  if (!server_id.empty())
53  {
54  server_id_ = ros::this_node::getName() + "/" + server_id;
55  }
56  else
57  {
59  }
60 
61  std::string update_topic = topic_ns + "/update";
62  std::string init_topic = update_topic + "_full";
63  std::string feedback_topic = topic_ns + "/feedback";
64 
65  init_pub_ = node_handle_.advertise<visualization_msgs::InteractiveMarkerInit>( init_topic, 100, true );
66  update_pub_ = node_handle_.advertise<visualization_msgs::InteractiveMarkerUpdate>( update_topic, 100 );
68 
70 
71  if ( spin_thread )
72  {
73  need_to_terminate_ = false;
74  spin_thread_.reset( new boost::thread(boost::bind(&InteractiveMarkerServer::spinThread, this)) );
75  }
76 
77  publishInit();
78 }
79 
80 
82 {
83  if (spin_thread_.get())
84  {
85  need_to_terminate_ = true;
86  spin_thread_->join();
87  }
88 
89  if ( node_handle_.ok() )
90  {
91  clear();
92  applyChanges();
93  }
94 }
95 
96 
98 {
99  while (node_handle_.ok())
100  {
101  if (need_to_terminate_)
102  {
103  break;
104  }
106  }
107 }
108 
109 
111 {
112  boost::recursive_mutex::scoped_lock lock( mutex_ );
113 
114  if ( pending_updates_.empty() )
115  {
116  return;
117  }
118 
119  M_UpdateContext::iterator update_it;
120 
121  visualization_msgs::InteractiveMarkerUpdate update;
122  update.type = visualization_msgs::InteractiveMarkerUpdate::UPDATE;
123 
124  update.markers.reserve( marker_contexts_.size() );
125  update.poses.reserve( marker_contexts_.size() );
126  update.erases.reserve( marker_contexts_.size() );
127 
128  for ( update_it = pending_updates_.begin(); update_it != pending_updates_.end(); update_it++ )
129  {
130  M_MarkerContext::iterator marker_context_it = marker_contexts_.find( update_it->first );
131 
132  switch ( update_it->second.update_type )
133  {
135  {
136  if ( marker_context_it == marker_contexts_.end() )
137  {
138  ROS_DEBUG("Creating new context for %s", update_it->first.c_str());
139  // create a new int_marker context
140  marker_context_it = marker_contexts_.insert( std::make_pair( update_it->first, MarkerContext() ) ).first;
141  // copy feedback cbs, in case they have been set before the marker context was created
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;
144  }
145 
146  marker_context_it->second.int_marker = update_it->second.int_marker;
147 
148  update.markers.push_back( marker_context_it->second.int_marker );
149  break;
150  }
151 
153  {
154  if ( marker_context_it == marker_contexts_.end() )
155  {
156  ROS_ERROR( "Pending pose update for non-existing marker found. This is a bug in InteractiveMarkerInterface." );
157  }
158  else
159  {
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;
162 
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 );
168  }
169  break;
170  }
171 
173  {
174  if ( marker_context_it != marker_contexts_.end() )
175  {
176  marker_contexts_.erase( update_it->first );
177  update.erases.push_back( update_it->first );
178  }
179  break;
180  }
181  }
182  }
183 
184  seq_num_++;
185 
186  publish( update );
187  publishInit();
188  pending_updates_.clear();
189 }
190 
191 
192 bool InteractiveMarkerServer::erase( const std::string &name )
193 {
194  boost::recursive_mutex::scoped_lock lock( mutex_ );
195 
196  pending_updates_[name].update_type = UpdateContext::ERASE;
197  return true;
198 }
199 
201 {
202  boost::recursive_mutex::scoped_lock lock( mutex_ );
203 
204  // erase all markers
205  pending_updates_.clear();
206  M_MarkerContext::iterator it;
207  for ( it = marker_contexts_.begin(); it != marker_contexts_.end(); it++ )
208  {
209  pending_updates_[it->first].update_type = UpdateContext::ERASE;
210  }
211 }
212 
213 
215 {
216  return marker_contexts_.empty();
217 }
218 
219 
220 std::size_t InteractiveMarkerServer::size() const
221 {
222  return marker_contexts_.size();
223 }
224 
225 
226 bool InteractiveMarkerServer::setPose( const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header )
227 {
228  boost::recursive_mutex::scoped_lock lock( mutex_ );
229 
230  M_MarkerContext::iterator marker_context_it = marker_contexts_.find( name );
231  M_UpdateContext::iterator update_it = pending_updates_.find( name );
232 
233  // if there's no marker and no pending addition for it, we can't update the pose
234  if ( marker_context_it == marker_contexts_.end() &&
235  ( update_it == pending_updates_.end() || update_it->second.update_type != UpdateContext::FULL_UPDATE ) )
236  {
237  return false;
238  }
239 
240  // keep the old header
241  if ( header.frame_id.empty() )
242  {
243  if ( marker_context_it != marker_contexts_.end() )
244  {
245  doSetPose( update_it, name, pose, marker_context_it->second.int_marker.header );
246  }
247  else if ( update_it != pending_updates_.end() )
248  {
249  doSetPose( update_it, name, pose, update_it->second.int_marker.header );
250  }
251  else
252  {
253  BOOST_ASSERT_MSG(false, "Marker does not exist and there is no pending creation.");
254  return false;
255  }
256  }
257  else
258  {
259  doSetPose( update_it, name, pose, header );
260  }
261  return true;
262 }
263 
264 bool InteractiveMarkerServer::setCallback( const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type )
265 {
266  boost::recursive_mutex::scoped_lock lock( mutex_ );
267 
268  M_MarkerContext::iterator marker_context_it = marker_contexts_.find( name );
269  M_UpdateContext::iterator update_it = pending_updates_.find( name );
270 
271  if ( marker_context_it == marker_contexts_.end() && update_it == pending_updates_.end() )
272  {
273  return false;
274  }
275 
276  // we need to overwrite both the callbacks for the actual marker
277  // and the update, if there's any
278 
279  if ( marker_context_it != marker_contexts_.end() )
280  {
281  // the marker exists, so we can just overwrite the existing callbacks
282  if ( feedback_type == DEFAULT_FEEDBACK_CB )
283  {
284  marker_context_it->second.default_feedback_cb = feedback_cb;
285  }
286  else
287  {
288  if ( feedback_cb )
289  {
290  marker_context_it->second.feedback_cbs[feedback_type] = feedback_cb;
291  }
292  else
293  {
294  marker_context_it->second.feedback_cbs.erase( feedback_type );
295  }
296  }
297  }
298 
299  if ( update_it != pending_updates_.end() )
300  {
301  if ( feedback_type == DEFAULT_FEEDBACK_CB )
302  {
303  update_it->second.default_feedback_cb = feedback_cb;
304  }
305  else
306  {
307  if ( feedback_cb )
308  {
309  update_it->second.feedback_cbs[feedback_type] = feedback_cb;
310  }
311  else
312  {
313  update_it->second.feedback_cbs.erase( feedback_type );
314  }
315  }
316  }
317  return true;
318 }
319 
320 void InteractiveMarkerServer::insert( const visualization_msgs::InteractiveMarker &int_marker )
321 {
322  boost::recursive_mutex::scoped_lock lock( mutex_ );
323 
324  M_UpdateContext::iterator update_it = pending_updates_.find( int_marker.name );
325  if ( update_it == pending_updates_.end() )
326  {
327  update_it = pending_updates_.insert( std::make_pair( int_marker.name, UpdateContext() ) ).first;
328  }
329 
330  update_it->second.update_type = UpdateContext::FULL_UPDATE;
331  update_it->second.int_marker = int_marker;
332 }
333 
334 void InteractiveMarkerServer::insert( const visualization_msgs::InteractiveMarker &int_marker,
335  FeedbackCallback feedback_cb, uint8_t feedback_type)
336 {
337  insert( int_marker );
338 
339  setCallback( int_marker.name, feedback_cb, feedback_type );
340 }
341 
342 bool InteractiveMarkerServer::get( std::string name, visualization_msgs::InteractiveMarker &int_marker ) const
343 {
344  boost::recursive_mutex::scoped_lock lock( mutex_ );
345 
346  M_UpdateContext::const_iterator update_it = pending_updates_.find( name );
347 
348  if ( update_it == pending_updates_.end() )
349  {
350  M_MarkerContext::const_iterator marker_context_it = marker_contexts_.find( name );
351  if ( marker_context_it == marker_contexts_.end() )
352  {
353  return false;
354  }
355 
356  int_marker = marker_context_it->second.int_marker;
357  return true;
358  }
359 
360  // if there's an update pending, we'll have to account for that
361  switch ( update_it->second.update_type )
362  {
364  return false;
365 
367  {
368  M_MarkerContext::const_iterator marker_context_it = marker_contexts_.find( name );
369  if ( marker_context_it == marker_contexts_.end() )
370  {
371  return false;
372  }
373  int_marker = marker_context_it->second.int_marker;
374  int_marker.pose = update_it->second.int_marker.pose;
375  return true;
376  }
377 
379  int_marker = update_it->second.int_marker;
380  return true;
381  }
382 
383  return false;
384 }
385 
387 {
388  boost::recursive_mutex::scoped_lock lock( mutex_ );
389 
390  visualization_msgs::InteractiveMarkerInit init;
391  init.server_id = server_id_;
392  init.seq_num = seq_num_;
393  init.markers.reserve( marker_contexts_.size() );
394 
395  M_MarkerContext::iterator it;
396  for ( it = marker_contexts_.begin(); it != marker_contexts_.end(); it++ )
397  {
398  ROS_DEBUG( "Publishing %s", it->second.int_marker.name.c_str() );
399  init.markers.push_back( it->second.int_marker );
400  }
401 
402  init_pub_.publish( init );
403 }
404 
406 {
407  boost::recursive_mutex::scoped_lock lock( mutex_ );
408 
409  M_MarkerContext::iterator marker_context_it = marker_contexts_.find( feedback->marker_name );
410 
411  // ignore feedback for non-existing markers
412  if ( marker_context_it == marker_contexts_.end() )
413  {
414  return;
415  }
416 
417  MarkerContext &marker_context = marker_context_it->second;
418 
419  // if two callers try to modify the same marker, reject (timeout= 1 sec)
420  if ( marker_context.last_client_id != feedback->client_id &&
421  (ros::Time::now() - marker_context.last_feedback).toSec() < 1.0 )
422  {
423  ROS_DEBUG( "Rejecting feedback for %s: conflicting feedback from separate clients.", feedback->marker_name.c_str() );
424  return;
425  }
426 
427  marker_context.last_feedback = ros::Time::now();
428  marker_context.last_client_id = feedback->client_id;
429 
430  if ( feedback->event_type == visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE )
431  {
432  if ( marker_context.int_marker.header.stamp == ros::Time(0) )
433  {
434  // keep the old header
435  doSetPose( pending_updates_.find( feedback->marker_name ), feedback->marker_name, feedback->pose, marker_context.int_marker.header );
436  }
437  else
438  {
439  doSetPose( pending_updates_.find( feedback->marker_name ), feedback->marker_name, feedback->pose, feedback->header );
440  }
441  }
442 
443  // call feedback handler
444  boost::unordered_map<uint8_t,FeedbackCallback>::iterator feedback_cb_it = marker_context.feedback_cbs.find( feedback->event_type );
445  if ( feedback_cb_it != marker_context.feedback_cbs.end() && feedback_cb_it->second )
446  {
447  // call type-specific callback
448  feedback_cb_it->second( feedback );
449  }
450  else if ( marker_context.default_feedback_cb )
451  {
452  // call default callback
453  marker_context.default_feedback_cb( feedback );
454  }
455 }
456 
457 
459 {
460  visualization_msgs::InteractiveMarkerUpdate empty_update;
461  empty_update.type = visualization_msgs::InteractiveMarkerUpdate::KEEP_ALIVE;
462  publish( empty_update );
463 }
464 
465 
466 void InteractiveMarkerServer::publish( visualization_msgs::InteractiveMarkerUpdate &update )
467 {
468  update.server_id = server_id_;
469  update.seq_num = seq_num_;
470  update_pub_.publish( update );
471 }
472 
473 
474 void InteractiveMarkerServer::doSetPose( M_UpdateContext::iterator update_it, const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header )
475 {
476  if ( update_it == pending_updates_.end() )
477  {
478  update_it = pending_updates_.insert( std::make_pair( name, UpdateContext() ) ).first;
479  update_it->second.update_type = UpdateContext::POSE_UPDATE;
480  }
481  else if ( update_it->second.update_type != UpdateContext::FULL_UPDATE )
482  {
483  update_it->second.update_type = UpdateContext::POSE_UPDATE;
484  }
485 
486  update_it->second.int_marker.pose = pose;
487  update_it->second.int_marker.header = header;
488  ROS_DEBUG( "Marker '%s' is now at %f, %f, %f", update_it->first.c_str(), pose.position.x, pose.position.y, pose.position.z );
489 }
490 
491 
492 }
void publish(const boost::shared_ptr< M > &message) const
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr
boost::unordered_map< uint8_t, FeedbackCallback > feedback_cbs
void processFeedback(const FeedbackConstPtr &feedback)
ROSCPP_DECL const std::string & getName()
boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
~InteractiveMarkerServer()
Destruction of the interface will lead to all managed markers being cleared.
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
void setCallbackQueue(CallbackQueueInterface *queue)
InteractiveMarkerServer(const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool get(std::string name, visualization_msgs::InteractiveMarker &int_marker) const
void doSetPose(M_UpdateContext::iterator update_it, const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header)
void insert(const visualization_msgs::InteractiveMarker &int_marker)
void publish(visualization_msgs::InteractiveMarkerUpdate &update)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
static Time now()
bool ok() const
bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


interactive_markers
Author(s): David Gossow
autogenerated on Sun Feb 3 2019 03:24:09