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>
37 
38 #include <boost/scoped_ptr.hpp>
39 #include <boost/thread/thread.hpp>
40 #include <boost/thread/recursive_mutex.hpp>
41 
42 #include <ros/ros.h>
43 #include <ros/callback_queue.h>
44 
45 
46 #include <boost/function.hpp>
47 #include <boost/unordered_map.hpp>
48 
49 namespace interactive_markers
50 {
51 
56 class InteractiveMarkerServer : boost::noncopyable
57 {
58 public:
59 
60  typedef visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr;
61  typedef boost::function< void ( const FeedbackConstPtr& ) > FeedbackCallback;
62 
63  static const uint8_t DEFAULT_FEEDBACK_CB = 255;
64 
72  InteractiveMarkerServer( const std::string &topic_ns, const std::string &server_id="", bool spin_thread = false );
73 
76 
81  void insert( const visualization_msgs::InteractiveMarker &int_marker );
82 
89  void insert( const visualization_msgs::InteractiveMarker &int_marker,
90  FeedbackCallback feedback_cb,
91  uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
92 
99  bool setPose( const std::string &name,
100  const geometry_msgs::Pose &pose,
101  const std_msgs::Header &header=std_msgs::Header() );
102 
107  bool erase( const std::string &name );
108 
111  void clear();
112 
116  bool empty() const;
117 
121  std::size_t size() const;
122 
133  bool setCallback( const std::string &name, FeedbackCallback feedback_cb,
134  uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
135 
138  void applyChanges();
139 
144  bool get( std::string name, visualization_msgs::InteractiveMarker &int_marker ) const;
145 
146 private:
147 
149  {
151  std::string last_client_id;
152  FeedbackCallback default_feedback_cb;
153  boost::unordered_map<uint8_t,FeedbackCallback> feedback_cbs;
154  visualization_msgs::InteractiveMarker int_marker;
155  };
156 
157  typedef boost::unordered_map< std::string, MarkerContext > M_MarkerContext;
158 
159  // represents an update to a single marker
161  {
162  enum {
165  ERASE
166  } update_type;
167  visualization_msgs::InteractiveMarker int_marker;
168  FeedbackCallback default_feedback_cb;
169  boost::unordered_map<uint8_t,FeedbackCallback> feedback_cbs;
170  };
171 
172  typedef boost::unordered_map< std::string, UpdateContext > M_UpdateContext;
173 
174  // main loop when spinning our own thread
175  // - process callbacks in our callback queue
176  // - process pending goals
177  void spinThread();
178 
179  // update marker pose & call user callback
180  void processFeedback( const FeedbackConstPtr& feedback );
181 
182  // send an empty update to keep the client GUIs happy
183  void keepAlive();
184 
185  // increase sequence number & publish an update
186  void publish( visualization_msgs::InteractiveMarkerUpdate &update );
187 
188  // publish the current complete state to the latched "init" topic.
189  void publishInit();
190 
191  // Update pose, schedule update without locking
192  void doSetPose( M_UpdateContext::iterator update_it,
193  const std::string &name,
194  const geometry_msgs::Pose &pose,
195  const std_msgs::Header &header );
196 
197  // contains the current state of all markers
198  M_MarkerContext marker_contexts_;
199 
200  // updates that have to be sent on the next publish
201  M_UpdateContext pending_updates_;
202 
203  // topic namespace to use
204  std::string topic_ns_;
205 
206  mutable boost::recursive_mutex mutex_;
207 
208  // these are needed when spinning up a dedicated thread
209  boost::scoped_ptr<boost::thread> spin_thread_;
212  volatile bool need_to_terminate_;
213 
214  // this is needed when running in non-threaded mode
216 
220 
221  uint64_t seq_num_;
222 
223  std::string server_id_;
224 };
225 
226 }
227 
228 #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
boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
~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
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)
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)
bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())


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