1 #ifndef __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H 2 #define __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H 10 #include <boost/utility/enable_if.hpp> 11 #include <boost/type_traits/is_void.hpp> 43 template<
class ROS_SERVICE_T>
48 virtual bool call(
typename ROS_SERVICE_T::Request& request,
typename ROS_SERVICE_T::Response& response)
const = 0;
51 template<
class ROS_SERVICE_T,
int variant = 0>
62 template<
class ROS_SERVICE_T>
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);
71 template<
class ROS_SERVICE_T,
int variant = 0>
85 virtual bool call(
typename ROS_SERVICE_T::Request& request,
typename ROS_SERVICE_T::Response& response)
const {
87 if (!proxy_operation_caller_->ready())
return false;
88 return Wrapper::call(*proxy_operation_caller_, request, response);
93 : proxy_operation_caller_(impl) {}
100 template<
class ROS_SERVICE_T,
int variant,
typename Enabled =
void>
101 struct ROSServiceServerOperationCallerWrapperNextVariant {
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> {
117 template<
class ROS_SERVICE_T,
int variant>
122 if (proxy_operation_caller->ready()) {
125 return ROSServiceServerOperationCallerWrapperNextVariant<ROS_SERVICE_T, variant>::connect(operation);
128 template<
class ROS_SERVICE_T>
155 return (impl_.get() != 0);
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);
180 return proxy_operation_.get() != NULL &&
182 proxy_operation_->getImplementation(),
193 template<
class ROS_SERVICE_T>
205 proxy_operation_.reset(
new ProxyOperationType(
"ROS_SERVICE_CLIENT_PROXY"));
212 dynamic_cast<ProxyOperationType*
>(proxy_operation_.get())->calls(
223 return client_.exists() && client_.isValid() && client_.call(request, response);
236 const std::string&
getType() {
return service_type_; }
247 template<
class ROS_SERVICE_T>
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'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_
RTT::OperationCaller< Signature > ProxyOperationCallerType
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)
void ProxyOperationCallerType
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.
std::string service_type_
static RTT_API ExecutionEngine * Instance()
virtual ~ROSServiceProxyBase()
bool orocos_operation_callback(typename ROS_SERVICE_T::Request &request, typename ROS_SERVICE_T::Response &response)
The callback for the RTT operation.
virtual ~ROSServiceServerOperationCallerBase()
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.
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)