rtt_rosservice_proxy.h
Go to the documentation of this file.
00001 #ifndef __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H
00002 #define __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <rtt/RTT.hpp>
00007 #include <rtt/plugin/ServicePlugin.hpp>
00008 
00010 class ROSServiceProxyBase
00011 {
00012 public:
00013   ROSServiceProxyBase(const std::string &service_name) : service_name_(service_name) { }
00015   const std::string& getServiceName() const { return service_name_; }
00016 private:
00018   std::string service_name_;
00019 };
00020 
00021 
00023 class ROSServiceServerProxyBase : public ROSServiceProxyBase
00024 { 
00025 public:
00026   ROSServiceServerProxyBase(const std::string &service_name) :
00027     ROSServiceProxyBase(service_name),
00028     proxy_operation_caller_()
00029   { }
00030   
00032   bool connect(RTT::TaskContext *owner, RTT::OperationInterfacePart* operation) {
00033     // Link the caller with the operation
00034     return proxy_operation_caller_->setImplementation(
00035         operation->getLocalOperation(),
00036         owner->engine());
00037   }
00038 
00039 protected:
00041   ros::ServiceServer server_;
00043   boost::shared_ptr<RTT::base::OperationCallerBaseInvoker> proxy_operation_caller_;
00044 };
00045 
00046 template<class ROS_SERVICE_T>
00047 class ROSServiceServerProxy : public ROSServiceServerProxyBase 
00048 {
00049 public:
00051   typedef RTT::OperationCaller<bool(typename ROS_SERVICE_T::Request&, typename ROS_SERVICE_T::Response&)> ProxyOperationCallerType;
00052 
00056   ROSServiceServerProxy(const std::string &service_name) :
00057     ROSServiceServerProxyBase(service_name)
00058   {
00059     // Construct operation caller
00060     proxy_operation_caller_.reset(new ProxyOperationCallerType("ROS_SERVICE_SERVER_PROXY"));
00061 
00062     // Construct the ROS service server
00063     ros::NodeHandle nh;
00064     server_ = nh.advertiseService(
00065         service_name, 
00066         &ROSServiceServerProxy<ROS_SERVICE_T>::ros_service_callback, 
00067         this);
00068   }
00069 
00070 private:
00071   
00073   bool ros_service_callback(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) {
00074     // Downcast the proxy operation caller
00075     ProxyOperationCallerType &proxy_operation_caller = *dynamic_cast<ProxyOperationCallerType*>(proxy_operation_caller_.get());
00076     // Check if the operation caller is ready, and then call it
00077     return proxy_operation_caller_->ready() && proxy_operation_caller(request, response);
00078   }
00079 };
00080 
00081 
00083 class ROSServiceClientProxyBase : public ROSServiceProxyBase
00084 {
00085 public:
00086   ROSServiceClientProxyBase(const std::string &service_name) : 
00087     ROSServiceProxyBase(service_name),
00088     proxy_operation_()
00089   { }
00090 
00092   bool connect(RTT::TaskContext *owner, RTT::base::OperationCallerBaseInvoker* operation_caller) {
00093     return proxy_operation_.get() != NULL &&
00094       operation_caller->setImplementation(
00095           proxy_operation_->getImplementation(),
00096           owner->engine());
00097   }
00098 
00099 protected:
00101   ros::ServiceClient client_;
00103   boost::shared_ptr<RTT::base::OperationBase> proxy_operation_;
00104 };
00105 
00106 template<class ROS_SERVICE_T>
00107 class ROSServiceClientProxy : public ROSServiceClientProxyBase 
00108 {
00109 public:
00110 
00112   typedef RTT::Operation<bool(typename ROS_SERVICE_T::Request&, typename ROS_SERVICE_T::Response&)> ProxyOperationType;
00113 
00114   ROSServiceClientProxy(const std::string &service_name) :
00115     ROSServiceClientProxyBase(service_name)
00116   {
00117     // Construct a new 
00118     proxy_operation_.reset(new ProxyOperationType("ROS_SERVICE_CLIENT_PROXY"));
00119 
00120     // Construct the underlying service client
00121     ros::NodeHandle nh;
00122     client_ = nh.serviceClient<ROS_SERVICE_T>(service_name);
00123 
00124     // Link the operation with the service client
00125     dynamic_cast<ProxyOperationType*>(proxy_operation_.get())->calls(
00126         &ROSServiceClientProxy<ROS_SERVICE_T>::orocos_operation_callback,
00127         this,
00128         RTT::ClientThread);
00129   }
00130 
00131 private:
00132   
00134   bool orocos_operation_callback(typename ROS_SERVICE_T::Request& request, typename ROS_SERVICE_T::Response& response) {
00135     // Make sure the ROS service client exists and then call it (blocking)
00136     return client_.exists() && client_.isValid() && client_.call(request, response);
00137   }
00138 };
00139 
00140 
00142 class ROSServiceProxyFactoryBase 
00143 {
00144 public:
00145 
00146   ROSServiceProxyFactoryBase(const std::string &service_type) : service_type_(service_type) { }
00147 
00149   const std::string& getType() { return service_type_; }
00150 
00152   virtual ROSServiceClientProxyBase* create_client_proxy(const std::string &service_name) = 0;
00154   virtual ROSServiceServerProxyBase* create_server_proxy(const std::string &service_name) = 0;
00155 
00156 private:
00157   std::string service_type_;
00158 };
00159 
00160 template<class ROS_SERVICE_T>
00161 class ROSServiceProxyFactory : public ROSServiceProxyFactoryBase 
00162 {
00163 public:
00164 
00165   ROSServiceProxyFactory(const std::string &service_type) : ROSServiceProxyFactoryBase(service_type) { }
00166 
00167   virtual ROSServiceClientProxyBase* create_client_proxy(const std::string &service_name) {
00168     return new ROSServiceClientProxy<ROS_SERVICE_T>(service_name);
00169   }
00170 
00171   virtual ROSServiceServerProxyBase* create_server_proxy( const std::string &service_name) {
00172     return new ROSServiceServerProxy<ROS_SERVICE_T>(service_name);
00173   }
00174 };
00175 
00176 #endif // ifndef __RTT_ROSCOMM_RTT_ROSSERVICE_PROXY_H


rtt_roscomm
Author(s): Ruben Smits, Jonathan Bohren
autogenerated on Wed Sep 16 2015 06:58:09