interactive_marker_server.h
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 
32 #ifndef INTERACTIVE_MARKER_SERVER
33 #define INTERACTIVE_MARKER_SERVER
34 
35 #include <visualization_msgs/InteractiveMarkerUpdate.h>
36 #include <visualization_msgs/InteractiveMarkerFeedback.h>
38 
39 #include <boost/scoped_ptr.hpp>
40 #include <boost/thread/thread.hpp>
41 #include <boost/thread/recursive_mutex.hpp>
42 
43 #include <ros/ros.h>
44 #include <ros/callback_queue.h>
45 
46 
47 #include <boost/function.hpp>
48 #include <boost/unordered_map.hpp>
49 
50 namespace interactive_markers
51 {
52 
57 class InteractiveMarkerServer : boost::noncopyable
58 {
59 public:
60 
61  typedef visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr;
62  typedef boost::function< void ( const FeedbackConstPtr& ) > FeedbackCallback;
63 
64  static const uint8_t DEFAULT_FEEDBACK_CB = 255;
65 
74  InteractiveMarkerServer( const std::string &topic_ns, const std::string &server_id="", bool spin_thread = false );
75 
79 
85  void insert( const visualization_msgs::InteractiveMarker &int_marker );
86 
94  void insert( const visualization_msgs::InteractiveMarker &int_marker,
95  FeedbackCallback feedback_cb,
96  uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
97 
105  bool setPose( const std::string &name,
106  const geometry_msgs::Pose &pose,
107  const std_msgs::Header &header=std_msgs::Header() );
108 
114  bool erase( const std::string &name );
115 
119  void clear();
120 
125  bool empty() const;
126 
131  std::size_t size() const;
132 
144  bool setCallback( const std::string &name, FeedbackCallback feedback_cb,
145  uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
146 
150  void applyChanges();
151 
157  bool get( std::string name, visualization_msgs::InteractiveMarker &int_marker ) const;
158 
159 private:
160 
162  {
164  std::string last_client_id;
165  FeedbackCallback default_feedback_cb;
166  boost::unordered_map<uint8_t,FeedbackCallback> feedback_cbs;
167  visualization_msgs::InteractiveMarker int_marker;
168  };
169 
170  typedef boost::unordered_map< std::string, MarkerContext > M_MarkerContext;
171 
172  // represents an update to a single marker
174  {
175  enum {
178  ERASE
179  } update_type;
180  visualization_msgs::InteractiveMarker int_marker;
181  FeedbackCallback default_feedback_cb;
182  boost::unordered_map<uint8_t,FeedbackCallback> feedback_cbs;
183  };
184 
185  typedef boost::unordered_map< std::string, UpdateContext > M_UpdateContext;
186 
187  // main loop when spinning our own thread
188  // - process callbacks in our callback queue
189  // - process pending goals
190  void spinThread();
191 
192  // update marker pose & call user callback
193  void processFeedback( const FeedbackConstPtr& feedback );
194 
195  // send an empty update to keep the client GUIs happy
196  void keepAlive();
197 
198  // increase sequence number & publish an update
199  void publish( visualization_msgs::InteractiveMarkerUpdate &update );
200 
201  // publish the current complete state to the latched "init" topic.
202  void publishInit();
203 
204  // Update pose, schedule update without locking
205  void doSetPose( M_UpdateContext::iterator update_it,
206  const std::string &name,
207  const geometry_msgs::Pose &pose,
208  const std_msgs::Header &header );
209 
210  // contains the current state of all markers
211  M_MarkerContext marker_contexts_;
212 
213  // updates that have to be sent on the next publish
214  M_UpdateContext pending_updates_;
215 
216  // topic namespace to use
217  std::string topic_ns_;
218 
219  mutable boost::recursive_mutex mutex_;
220 
221  // these are needed when spinning up a dedicated thread
222  boost::scoped_ptr<boost::thread> spin_thread_;
225  volatile bool need_to_terminate_;
226 
227  // this is needed when running in non-threaded mode
229 
233 
234  uint64_t seq_num_;
235 
236  std::string server_id_;
237 };
238 
239 }
240 
241 #endif
visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr
boost::unordered_map< uint8_t, FeedbackCallback > feedback_cbs
void processFeedback(const FeedbackConstPtr &feedback)
boost::unordered_map< std::string, MarkerContext > M_MarkerContext
#define INTERACTIVE_MARKERS_PUBLIC
boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
INTERACTIVE_MARKERS_PUBLIC ~InteractiveMarkerServer()
Destruction of the interface will lead to all managed markers being cleared.
boost::unordered_map< std::string, UpdateContext > M_UpdateContext
boost::unordered_map< uint8_t, FeedbackCallback > feedback_cbs
INTERACTIVE_MARKERS_PUBLIC InteractiveMarkerServer(const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false)
void doSetPose(M_UpdateContext::iterator update_it, const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
void publish(visualization_msgs::InteractiveMarkerUpdate &update)
INTERACTIVE_MARKERS_PUBLIC bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
INTERACTIVE_MARKERS_PUBLIC bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
INTERACTIVE_MARKERS_PUBLIC bool erase(const std::string &name)
INTERACTIVE_MARKERS_PUBLIC bool empty() const
INTERACTIVE_MARKERS_PUBLIC std::size_t size() const


interactive_markers
Author(s): David Gossow, William Woodall
autogenerated on Thu Oct 8 2020 04:02:35