rtt_rosservice_proxy.h
Go to the documentation of this file.
1 #ifndef __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H
2 #define __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H
3 
4 #include <ros/ros.h>
5 
6 #include <rtt/RTT.hpp>
9 
10 #include <boost/utility/enable_if.hpp>
11 #include <boost/type_traits/is_void.hpp>
12 
15 {
16 public:
17  ROSServiceProxyBase(const std::string &service_name) : service_name_(service_name) { }
18  virtual ~ROSServiceProxyBase() { }
20  const std::string& getServiceName() const { return service_name_; }
21 private:
23  std::string service_name_;
24 };
25 
26 
29 {
30 public:
31  ROSServiceServerProxyBase(const std::string &service_name) :
32  ROSServiceProxyBase(service_name)
33  { }
34 
36  virtual bool connect(RTT::TaskContext *owner, RTT::OperationInterfacePart* operation) = 0;
37 
38 protected:
41 };
42 
43 template<class ROS_SERVICE_T>
45 public:
48  virtual bool call(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) const = 0;
49 };
50 
51 template<class ROS_SERVICE_T, int variant = 0>
54 };
55 
56 // Default implementation of an OperationCaller that fowards ROS service calls to Orocos operations
57 // that have the default bool(Request&, Response&) signature. You can add more variants of this class
58 // to add support for custom operation types.
59 //
60 // See package std_srvs for an example.
61 //
62 template<class ROS_SERVICE_T>
63 struct ROSServiceServerOperationCallerWrapper<ROS_SERVICE_T,0> {
64  typedef bool Signature(typename ROS_SERVICE_T::Request&, typename ROS_SERVICE_T::Response&);
66  template <typename Callable> static bool call(Callable& call, typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) {
67  return call(request, response);
68  }
69 };
70 
71 template<class ROS_SERVICE_T, int variant = 0>
73 public:
75 
78 
82 
83  static Ptr connect(RTT::OperationInterfacePart* operation);
84 
85  virtual bool call(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) const {
86  // Check if the operation caller is ready, and then call it.
87  if (!proxy_operation_caller_->ready()) return false;
88  return Wrapper::call(*proxy_operation_caller_, request, response);
89  }
90 
91 private:
93  : proxy_operation_caller_(impl) {}
94 
95  ProxyOperationCallerTypePtr proxy_operation_caller_;
96 };
97 
98 namespace {
99 
100 template<class ROS_SERVICE_T, int variant, typename Enabled = void>
101 struct ROSServiceServerOperationCallerWrapperNextVariant {
103  static Ptr connect(RTT::OperationInterfacePart*) { return Ptr(); }
104 };
105 
106 template<class ROS_SERVICE_T, int variant>
107 struct ROSServiceServerOperationCallerWrapperNextVariant<ROS_SERVICE_T, variant,
108  typename boost::disable_if<boost::is_void<typename ROSServiceServerOperationCallerWrapper<ROS_SERVICE_T, variant + 1>::ProxyOperationCallerType> >::type> {
110  static Ptr connect(RTT::OperationInterfacePart* operation) {
112  }
113 };
114 
115 }
116 
117 template<class ROS_SERVICE_T, int variant>
120  ProxyOperationCallerTypePtr proxy_operation_caller
121  = boost::make_shared<ProxyOperationCallerType>(operation->getLocalOperation(), RTT::internal::GlobalEngine::Instance());
122  if (proxy_operation_caller->ready()) {
123  return Ptr(new ROSServiceServerOperationCaller<ROS_SERVICE_T, variant>(proxy_operation_caller));
124  }
125  return ROSServiceServerOperationCallerWrapperNextVariant<ROS_SERVICE_T, variant>::connect(operation);
126 }
127 
128 template<class ROS_SERVICE_T>
130 {
131 public:
135  ROSServiceServerProxy(const std::string &service_name) :
136  ROSServiceServerProxyBase(service_name)
137  {
138  // Construct the ROS service server
139  ros::NodeHandle nh;
140  server_ = nh.advertiseService(
141  service_name,
143  this);
144  }
145 
147  {
148  // Clean-up advertized ROS services
149  server_.shutdown();
150  }
151 
153  {
155  return (impl_.get() != 0);
156  }
157 
158 private:
160  bool ros_service_callback(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) {
161  if (!impl_) return false;
162  return impl_->call(request, response);
163  }
164 
166 };
167 
168 
171 {
172 public:
173  ROSServiceClientProxyBase(const std::string &service_name) :
174  ROSServiceProxyBase(service_name),
175  proxy_operation_()
176  { }
177 
180  return proxy_operation_.get() != NULL &&
181  operation_caller->setImplementation(
182  proxy_operation_->getImplementation(),
183  owner->engine());
184  }
185 
186 protected:
191 };
192 
193 template<class ROS_SERVICE_T>
195 {
196 public:
197 
200 
201  ROSServiceClientProxy(const std::string &service_name) :
202  ROSServiceClientProxyBase(service_name)
203  {
204  // Construct a new
205  proxy_operation_.reset(new ProxyOperationType("ROS_SERVICE_CLIENT_PROXY"));
206 
207  // Construct the underlying service client
208  ros::NodeHandle nh;
209  client_ = nh.serviceClient<ROS_SERVICE_T>(service_name);
210 
211  // Link the operation with the service client
212  dynamic_cast<ProxyOperationType*>(proxy_operation_.get())->calls(
214  this,
216  }
217 
218 private:
219 
221  bool orocos_operation_callback(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) {
222  // Make sure the ROS service client exists and then call it (blocking)
223  return client_.exists() && client_.isValid() && client_.call(request, response);
224  }
225 };
226 
227 
230 {
231 public:
232 
233  ROSServiceProxyFactoryBase(const std::string &service_type) : service_type_(service_type) { }
234 
236  const std::string& getType() { return service_type_; }
237 
239  virtual ROSServiceClientProxyBase* create_client_proxy(const std::string &service_name) = 0;
241  virtual ROSServiceServerProxyBase* create_server_proxy(const std::string &service_name) = 0;
242 
243 private:
244  std::string service_type_;
245 };
246 
247 template<class ROS_SERVICE_T>
249 {
250 public:
251 
252  ROSServiceProxyFactory(const std::string &service_type) : ROSServiceProxyFactoryBase(service_type) { }
253 
254  virtual ROSServiceClientProxyBase* create_client_proxy(const std::string &service_name) {
255  return new ROSServiceClientProxy<ROS_SERVICE_T>(service_name);
256  }
257 
258  virtual ROSServiceServerProxyBase* create_server_proxy( const std::string &service_name) {
259  return new ROSServiceServerProxy<ROS_SERVICE_T>(service_name);
260  }
261 };
262 
263 #endif // ifndef __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSServiceServerProxy(const std::string &service_name)
Construct a ROS service server and associate it with an Orocos task&#39;s required interface and operatio...
virtual bool setImplementation(boost::shared_ptr< base::DisposableInterface > impl, ExecutionEngine *caller=0)=0
ros::ServiceServer server_
The underlying ROS service server.
ROSServiceServerOperationCallerBase< ROS_SERVICE_T >::Ptr Ptr
ProxyOperationCallerTypePtr proxy_operation_caller_
bool connect(RTT::TaskContext *owner, RTT::base::OperationCallerBaseInvoker *operation_caller)
Connect an operation caller with this proxy.
Wrapper::ProxyOperationCallerType ProxyOperationCallerType
Default operation caller for a ROS service server proxy.
bool call(const std::string &service_name, MReq &req, MRes &res)
boost::shared_ptr< ROSServiceServerOperationCallerBase< ROS_SERVICE_T > > Ptr
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static bool call(Callable &call, typename ROS_SERVICE_T::Request &request, typename ROS_SERVICE_T::Response &response)
ROSServiceServerOperationCaller(const boost::shared_ptr< ProxyOperationCallerType > &impl)
ROSServiceClientProxyBase(const std::string &service_name)
ROSServiceClientProxy(const std::string &service_name)
ROSServiceProxyBase(const std::string &service_name)
virtual bool call(typename ROS_SERVICE_T::Request &request, typename ROS_SERVICE_T::Response &response) const
ROSServiceProxyFactory(const std::string &service_type)
boost::shared_ptr< RTT::base::OperationBase > proxy_operation_
The underlying RTT operation.
bool Signature(typename ROS_SERVICE_T::Request &, typename ROS_SERVICE_T::Response &)
virtual bool connect(RTT::TaskContext *, RTT::OperationInterfacePart *operation)
Connect an RTT Operation to this ROS service server.
static RTT_API ExecutionEngine * Instance()
bool orocos_operation_callback(typename ROS_SERVICE_T::Request &request, typename ROS_SERVICE_T::Response &response)
The callback for the RTT operation.
boost::shared_ptr< ROSServiceServerOperationCallerBase< ROS_SERVICE_T > > impl_
virtual ROSServiceClientProxyBase * create_client_proxy(const std::string &service_name)
Get a proxy to a ROS service client.
Abstract factory for ROS Service Proxy Factories.
virtual RTT_API boost::shared_ptr< base::DisposableInterface > getLocalOperation() const
RTT::Operation< bool(typename ROS_SERVICE_T::Request &, typename ROS_SERVICE_T::Response &)> ProxyOperationType
The proxy RTT operation type for this ROS service.
std::string service_name_
ROS Service name (fully qualified)
Abstract ROS Service Client Proxy.
ROSServiceProxyFactoryBase(const std::string &service_type)
ROSServiceServerProxyBase(const std::string &service_name)
ROSServiceServerOperationCallerWrapper< ROS_SERVICE_T, variant > Wrapper
The wrapper type for this variant.
const std::string & getServiceName() const
Get the name of the ROS service.
Abstract ROS Service Server Proxy.
bool ros_service_callback(typename ROS_SERVICE_T::Request &request, typename ROS_SERVICE_T::Response &response)
The callback called by the ROS service server when this service is invoked.
boost::shared_ptr< ProxyOperationCallerType > ProxyOperationCallerTypePtr
const std::string & getType()
Get the ROS service type.
ClientThread
Abstract ROS Service Proxy.
const ExecutionEngine * engine() const
ros::ServiceClient client_
The underlying ROS service client.
virtual ROSServiceServerProxyBase * create_server_proxy(const std::string &service_name)
Get a proxy to a ROS service server.
static Ptr connect(RTT::OperationInterfacePart *operation)


rtt_roscomm
Author(s): Ruben Smits, Jonathan Bohren
autogenerated on Mon May 10 2021 02:45:04