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/thread/recursive_mutex.hpp>
38 #include <boost/function.hpp>
39 #include <boost/unordered_map.hpp>
40 
41 #include <string>
42 
43 #include <ros/subscriber.h>
44 #include <ros/node_handle.h>
45 
46 #include <tf2_ros/buffer.h>
47 
48 #include <visualization_msgs/InteractiveMarkerInit.h>
49 #include <visualization_msgs/InteractiveMarkerUpdate.h>
51 
52 #include "detail/state_machine.h"
53 
54 namespace interactive_markers
55 {
56 
57 class SingleClient;
58 
69 class InteractiveMarkerClient : boost::noncopyable
70 {
71 public:
72 
73  enum StatusT {
74  OK = 0,
75  WARN = 1,
76  ERROR = 2
77  };
78 
79  typedef visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr;
80  typedef visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr;
81 
82  typedef boost::function< void ( const UpdateConstPtr& ) > UpdateCallback;
83  typedef boost::function< void ( const InitConstPtr& ) > InitCallback;
84  typedef boost::function< void ( const std::string& ) > ResetCallback;
85  typedef boost::function< void ( StatusT, const std::string&, const std::string& ) > StatusCallback;
86 
92  const std::string& target_frame = "",
93  const std::string &topic_ns = "" );
94 
98 
101  void subscribe( std::string topic_ns );
102 
105  void shutdown();
106 
109  void update();
110 
113  void setTargetFrame( std::string target_frame );
114 
117  void setInitCb( const InitCallback& cb );
118 
121  void setUpdateCb( const UpdateCallback& cb );
122 
125  void setResetCb( const ResetCallback& cb );
126 
129  void setStatusCb( const StatusCallback& cb );
130 
133 
134 private:
135 
136  // Process message from the init or update channel
137  template<class MsgConstPtrT>
138  void process( const MsgConstPtrT& msg );
139 
141 
142  enum StateT
143  {
147  };
148 
150 
151  std::string topic_ns_;
152 
155 
156  // subscribe to the init channel
157  void subscribeInit();
158 
159  // subscribe to the init channel
160  void subscribeUpdate();
161 
162  void statusCb( StatusT status, const std::string& server_id, const std::string& msg );
163 
165  typedef boost::unordered_map<std::string, SingleClientPtr> M_SingleClient;
167  boost::recursive_mutex publisher_contexts_mutex_;
168 
170  std::string target_frame_;
171 
172 public:
173  // for internal usage
175  {
176  void initCb( const InitConstPtr& i ) const {
177  if (init_cb_) init_cb_( i ); }
178  void updateCb( const UpdateConstPtr& u ) const {
179  if (update_cb_) update_cb_( u ); }
180  void resetCb( const std::string& s ) const {
181  if (reset_cb_) reset_cb_(s); }
182  void statusCb( StatusT s, const std::string& id, const std::string& m ) const {
183  if (status_cb_) status_cb_(s,id,m); }
184 
185  void setInitCb( InitCallback init_cb ) {
186  init_cb_ = init_cb;
187  }
188  void setUpdateCb( UpdateCallback update_cb ) {
189  update_cb_ = update_cb;
190  }
191  void setResetCb( ResetCallback reset_cb ) {
192  reset_cb_ = reset_cb;
193  }
194  void setStatusCb( StatusCallback status_cb ) {
195  status_cb_ = status_cb;
196  }
197 
198  private:
203  };
204 
205  // handle init message
206  void processInit( const InitConstPtr& msg );
207 
208  // handle update message
209  void processUpdate( const UpdateConstPtr& msg );
210 
211 private:
213 
214  // this is the real (external) status callback
216 
217  // this allows us to detect if a server died (in most cases)
219 
220  // if false, auto-completed markers will have alpha = 1.0
222 };
223 
224 
225 
226 }
227 
228 #endif
interactive_markers::InteractiveMarkerClient::tf_
tf2_ros::Buffer & tf_
Definition: interactive_marker_client.h:169
interactive_markers::InteractiveMarkerClient::StatusT
StatusT
Definition: interactive_marker_client.h:73
node_handle.h
interactive_markers::InteractiveMarkerClient::CbCollection::init_cb_
InitCallback init_cb_
Definition: interactive_marker_client.h:199
interactive_markers::InteractiveMarkerClient::subscribeUpdate
void subscribeUpdate()
Definition: interactive_marker_client.cpp:133
interactive_markers::InteractiveMarkerClient::ERROR
@ ERROR
Definition: interactive_marker_client.h:76
boost::shared_ptr
interactive_markers::InteractiveMarkerClient::WARN
@ WARN
Definition: interactive_marker_client.h:75
interactive_markers::InteractiveMarkerClient::setResetCb
INTERACTIVE_MARKERS_PUBLIC void setResetCb(const ResetCallback &cb)
Set callback for resetting one server connection.
Definition: interactive_marker_client.cpp:85
interactive_markers::InteractiveMarkerClient::StatusCallback
boost::function< void(StatusT, const std::string &, const std::string &) > StatusCallback
Definition: interactive_marker_client.h:85
interactive_markers::InteractiveMarkerClient::status_cb_
StatusCallback status_cb_
Definition: interactive_marker_client.h:215
interactive_markers::InteractiveMarkerClient::CbCollection::statusCb
void statusCb(StatusT s, const std::string &id, const std::string &m) const
Definition: interactive_marker_client.h:182
s
XmlRpcServer s
interactive_markers::InteractiveMarkerClient::setEnableAutocompleteTransparency
INTERACTIVE_MARKERS_PUBLIC void setEnableAutocompleteTransparency(bool enable)
Definition: interactive_marker_client.h:132
interactive_markers::InteractiveMarkerClient::SingleClientPtr
boost::shared_ptr< SingleClient > SingleClientPtr
Definition: interactive_marker_client.h:164
interactive_markers::InteractiveMarkerClient::InitConstPtr
visualization_msgs::InteractiveMarkerInitConstPtr InitConstPtr
Definition: interactive_marker_client.h:80
interactive_markers::InteractiveMarkerClient::enable_autocomplete_transparency_
bool enable_autocomplete_transparency_
Definition: interactive_marker_client.h:221
interactive_markers::InteractiveMarkerClient::CbCollection::update_cb_
UpdateCallback update_cb_
Definition: interactive_marker_client.h:200
interactive_markers::InteractiveMarkerClient::setInitCb
INTERACTIVE_MARKERS_PUBLIC void setInitCb(const InitCallback &cb)
Set callback for init messages.
Definition: interactive_marker_client.cpp:75
interactive_markers::InteractiveMarkerClient::processInit
void processInit(const InitConstPtr &msg)
Definition: interactive_marker_client.cpp:208
interactive_markers::InteractiveMarkerClient::INIT
@ INIT
Definition: interactive_marker_client.h:145
buffer.h
interactive_markers::InteractiveMarkerClient::UpdateCallback
boost::function< void(const UpdateConstPtr &) > UpdateCallback
Definition: interactive_marker_client.h:82
interactive_markers::InteractiveMarkerClient::CbCollection::setInitCb
void setInitCb(InitCallback init_cb)
Definition: interactive_marker_client.h:185
interactive_markers::StateMachine
Definition: state_machine.h:48
interactive_markers::InteractiveMarkerClient::~InteractiveMarkerClient
INTERACTIVE_MARKERS_PUBLIC ~InteractiveMarkerClient()
Will cause a 'reset' call for all server ids.
Definition: interactive_marker_client.cpp:62
interactive_markers::InteractiveMarkerClient::setTargetFrame
INTERACTIVE_MARKERS_PUBLIC void setTargetFrame(std::string target_frame)
Change the target frame and reset the connection.
Definition: interactive_marker_client.cpp:95
interactive_markers::InteractiveMarkerClient::CbCollection::setStatusCb
void setStatusCb(StatusCallback status_cb)
Definition: interactive_marker_client.h:194
interactive_markers::InteractiveMarkerClient::OK
@ OK
Definition: interactive_marker_client.h:74
interactive_markers::InteractiveMarkerClient::subscribe
INTERACTIVE_MARKERS_PUBLIC void subscribe(std::string topic_ns)
Subscribe to the topics topic_ns/update and topic_ns/init.
Definition: interactive_marker_client.cpp:68
INTERACTIVE_MARKERS_PUBLIC
#define INTERACTIVE_MARKERS_PUBLIC
Definition: visibility_control.hpp:64
interactive_markers::InteractiveMarkerClient::subscribeInit
void subscribeInit()
Definition: interactive_marker_client.cpp:151
interactive_markers::InteractiveMarkerClient::CbCollection::resetCb
void resetCb(const std::string &s) const
Definition: interactive_marker_client.h:180
interactive_markers::InteractiveMarkerClient::update
INTERACTIVE_MARKERS_PUBLIC void update()
Update tf info, call callbacks.
Definition: interactive_marker_client.cpp:218
interactive_markers::InteractiveMarkerClient::RUNNING
@ RUNNING
Definition: interactive_marker_client.h:146
interactive_markers::InteractiveMarkerClient::publisher_contexts_mutex_
boost::recursive_mutex publisher_contexts_mutex_
Definition: interactive_marker_client.h:167
interactive_markers::InteractiveMarkerClient::CbCollection::updateCb
void updateCb(const UpdateConstPtr &u) const
Definition: interactive_marker_client.h:178
subscriber.h
interactive_markers::InteractiveMarkerClient::ResetCallback
boost::function< void(const std::string &) > ResetCallback
Definition: interactive_marker_client.h:84
interactive_markers::InteractiveMarkerClient::CbCollection::status_cb_
StatusCallback status_cb_
Definition: interactive_marker_client.h:202
interactive_markers::InteractiveMarkerClient::CbCollection::setResetCb
void setResetCb(ResetCallback reset_cb)
Definition: interactive_marker_client.h:191
tf2_ros::Buffer
interactive_markers::InteractiveMarkerClient::setUpdateCb
INTERACTIVE_MARKERS_PUBLIC void setUpdateCb(const UpdateCallback &cb)
Set callback for update messages.
Definition: interactive_marker_client.cpp:80
interactive_markers::InteractiveMarkerClient::CbCollection::initCb
void initCb(const InitConstPtr &i) const
Definition: interactive_marker_client.h:176
interactive_markers::InteractiveMarkerClient::setStatusCb
INTERACTIVE_MARKERS_PUBLIC void setStatusCb(const StatusCallback &cb)
Set callback for status updates.
Definition: interactive_marker_client.cpp:90
interactive_markers::InteractiveMarkerClient::StateT
StateT
Definition: interactive_marker_client.h:142
interactive_markers::InteractiveMarkerClient
Definition: interactive_marker_client.h:69
state_machine.h
interactive_markers::InteractiveMarkerClient::statusCb
void statusCb(StatusT status, const std::string &server_id, const std::string &msg)
Definition: interactive_marker_client.cpp:273
interactive_markers::InteractiveMarkerClient::shutdown
INTERACTIVE_MARKERS_PUBLIC void shutdown()
Unsubscribe, clear queues & call reset callbacks.
Definition: interactive_marker_client.cpp:114
interactive_markers::InteractiveMarkerClient::callbacks_
CbCollection callbacks_
Definition: interactive_marker_client.h:212
interactive_markers::InteractiveMarkerClient::topic_ns_
std::string topic_ns_
Definition: interactive_marker_client.h:151
interactive_markers::InteractiveMarkerClient::CbCollection::setUpdateCb
void setUpdateCb(UpdateCallback update_cb)
Definition: interactive_marker_client.h:188
interactive_markers::InteractiveMarkerClient::IDLE
@ IDLE
Definition: interactive_marker_client.h:144
interactive_markers::InteractiveMarkerClient::process
void process(const MsgConstPtrT &msg)
Definition: interactive_marker_client.cpp:169
interactive_markers::InteractiveMarkerClient::InitCallback
boost::function< void(const InitConstPtr &) > InitCallback
Definition: interactive_marker_client.h:83
interactive_markers::InteractiveMarkerClient::InteractiveMarkerClient
INTERACTIVE_MARKERS_PUBLIC InteractiveMarkerClient(tf2_ros::Buffer &tf, const std::string &target_frame="", const std::string &topic_ns="")
Definition: interactive_marker_client.cpp:45
interactive_markers::InteractiveMarkerClient::UpdateConstPtr
visualization_msgs::InteractiveMarkerUpdateConstPtr UpdateConstPtr
Definition: interactive_marker_client.h:79
visibility_control.hpp
interactive_markers::InteractiveMarkerClient::init_sub_
ros::Subscriber init_sub_
Definition: interactive_marker_client.h:154
interactive_markers::InteractiveMarkerClient::update_sub_
ros::Subscriber update_sub_
Definition: interactive_marker_client.h:153
interactive_markers::InteractiveMarkerClient::last_num_publishers_
uint32_t last_num_publishers_
Definition: interactive_marker_client.h:218
target_frame
std::string target_frame
Definition: client_test.cpp:72
interactive_markers::InteractiveMarkerClient::M_SingleClient
boost::unordered_map< std::string, SingleClientPtr > M_SingleClient
Definition: interactive_marker_client.h:165
interactive_markers::InteractiveMarkerClient::CbCollection
Definition: interactive_marker_client.h:174
interactive_markers
Definition: message_context.h:45
interactive_markers::InteractiveMarkerClient::publisher_contexts_
M_SingleClient publisher_contexts_
Definition: interactive_marker_client.h:166
interactive_markers::InteractiveMarkerClient::target_frame_
std::string target_frame_
Definition: interactive_marker_client.h:170
interactive_markers::InteractiveMarkerClient::state_
StateMachine< StateT > state_
Definition: interactive_marker_client.h:149
ros::NodeHandle
ros::Subscriber
interactive_markers::InteractiveMarkerClient::nh_
ros::NodeHandle nh_
Definition: interactive_marker_client.h:140
interactive_markers::InteractiveMarkerClient::CbCollection::reset_cb_
ResetCallback reset_cb_
Definition: interactive_marker_client.h:201
interactive_markers::InteractiveMarkerClient::processUpdate
void processUpdate(const UpdateConstPtr &msg)
Definition: interactive_marker_client.cpp:213


interactive_markers
Author(s): David Gossow, William Woodall
autogenerated on Fri Oct 27 2023 02:31:54