interactive_marker_client.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_CLIENT
33 #define INTERACTIVE_MARKER_CLIENT
34 
35 #include <boost/shared_ptr.hpp>
36 #include <boost/thread/mutex.hpp>
37 #include <boost/function.hpp>
38 #include <boost/unordered_map.hpp>
39 
40 #include <string>
41 
42 #include <ros/subscriber.h>
43 #include <ros/node_handle.h>
44 
45 #include <tf/tf.h>
46 
47 #include <visualization_msgs/InteractiveMarkerInit.h>
48 #include <visualization_msgs/InteractiveMarkerUpdate.h>
49 
50 #include "detail/state_machine.h"
51 
52 namespace interactive_markers
53 {
54 
55 class SingleClient;
56 
67 class InteractiveMarkerClient : boost::noncopyable
68 {
69 public:
70 
71  enum StatusT {
72  OK = 0,
73  WARN = 1,
74  ERROR = 2
75  };
76 
77  typedef visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr;
78  typedef visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr;
79 
80  typedef boost::function< void ( const UpdateConstPtr& ) > UpdateCallback;
81  typedef boost::function< void ( const InitConstPtr& ) > InitCallback;
82  typedef boost::function< void ( const std::string& ) > ResetCallback;
83  typedef boost::function< void ( StatusT, const std::string&, const std::string& ) > StatusCallback;
84 
89  const std::string& target_frame = "",
90  const std::string &topic_ns = "" );
91 
94 
96  void subscribe( std::string topic_ns );
97 
99  void shutdown();
100 
102  void update();
103 
105  void setTargetFrame( std::string target_frame );
106 
108  void setInitCb( const InitCallback& cb );
109 
111  void setUpdateCb( const UpdateCallback& cb );
112 
114  void setResetCb( const ResetCallback& cb );
115 
117  void setStatusCb( const StatusCallback& cb );
118 
120 
121 private:
122 
123  // Process message from the init or update channel
124  template<class MsgConstPtrT>
125  void process( const MsgConstPtrT& msg );
126 
128 
129  enum StateT
130  {
134  };
135 
137 
138  std::string topic_ns_;
139 
142 
143  // subscribe to the init channel
144  void subscribeInit();
145 
146  // subscribe to the init channel
147  void subscribeUpdate();
148 
149  void statusCb( StatusT status, const std::string& server_id, const std::string& msg );
150 
152  typedef boost::unordered_map<std::string, SingleClientPtr> M_SingleClient;
153  M_SingleClient publisher_contexts_;
155 
157  std::string target_frame_;
158 
159 public:
160  // for internal usage
162  {
163  void initCb( const InitConstPtr& i ) const {
164  if (init_cb_) init_cb_( i ); }
165  void updateCb( const UpdateConstPtr& u ) const {
166  if (update_cb_) update_cb_( u ); }
167  void resetCb( const std::string& s ) const {
168  if (reset_cb_) reset_cb_(s); }
169  void statusCb( StatusT s, const std::string& id, const std::string& m ) const {
170  if (status_cb_) status_cb_(s,id,m); }
171 
172  void setInitCb( InitCallback init_cb ) {
173  init_cb_ = init_cb;
174  }
175  void setUpdateCb( UpdateCallback update_cb ) {
176  update_cb_ = update_cb;
177  }
178  void setResetCb( ResetCallback reset_cb ) {
179  reset_cb_ = reset_cb;
180  }
181  void setStatusCb( StatusCallback status_cb ) {
182  status_cb_ = status_cb;
183  }
184 
185  private:
186  InitCallback init_cb_;
187  UpdateCallback update_cb_;
188  ResetCallback reset_cb_;
189  StatusCallback status_cb_;
190  };
191 
192  // handle init message
193  void processInit( const InitConstPtr& msg );
194 
195  // handle update message
196  void processUpdate( const UpdateConstPtr& msg );
197 
198 private:
200 
201  // this is the real (external) status callback
202  StatusCallback status_cb_;
203 
204  // this allows us to detect if a server died (in most cases)
206 
207  // if false, auto-completed markers will have alpha = 1.0
209 };
210 
211 
212 
213 }
214 
215 #endif
visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr
std::string target_frame
Definition: client_test.cpp:74
void shutdown()
Unsubscribe, clear queues & call reset callbacks.
void setInitCb(const InitCallback &cb)
Set callback for init messages.
boost::function< void(StatusT, const std::string &, const std::string &) > StatusCallback
boost::function< void(const InitConstPtr &) > InitCallback
boost::unordered_map< std::string, SingleClientPtr > M_SingleClient
void setResetCb(const ResetCallback &cb)
Set callback for resetting one server connection.
void subscribe(std::string topic_ns)
Subscribe to the topics topic_ns/update and topic_ns/init.
void setUpdateCb(const UpdateCallback &cb)
Set callback for update messages.
void setStatusCb(const StatusCallback &cb)
Set callback for status updates.
InteractiveMarkerClient(tf::Transformer &tf, const std::string &target_frame="", const std::string &topic_ns="")
~InteractiveMarkerClient()
Will cause a &#39;reset&#39; call for all server ids.
boost::function< void(const std::string &) > ResetCallback
visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr
void statusCb(StatusT status, const std::string &server_id, const std::string &msg)
void update()
Update tf info, call callbacks.
boost::function< void(const UpdateConstPtr &) > UpdateCallback
void statusCb(StatusT s, const std::string &id, const std::string &m) const
void setTargetFrame(std::string target_frame)
Change the target frame and reset the connection.


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