Go to the documentation of this file.00001
00025 #ifndef _BCAP_SERVICE_H_
00026 #define _BCAP_SERVICE_H_
00027
00028 #include <ros/ros.h>
00029 #include <boost/interprocess/smart_ptr/unique_ptr.hpp>
00030
00031 #include "variant_allocator.h"
00032 #include "bcap_service/bcap.h"
00033 #include "bcap_core/dn_common.h"
00034 #include "bcap_core/dn_device.h"
00035
00036 typedef std::pair<int32_t,uint32_t> KeyHandle;
00037 typedef std::vector<KeyHandle> KeyHandle_Vec;
00038
00039 struct variant_deleter {
00040 void operator()(VARIANT *p) const {
00041 VariantClear(p);
00042 delete p;
00043 }
00044 };
00045
00046 typedef boost::interprocess::unique_ptr<VARIANT, variant_deleter> VARIANT_Ptr;
00047 typedef std::vector<VARIANT, VariantAllocator<VARIANT> > VARIANT_Vec;
00048
00049 namespace bcap_service {
00050
00051 class BCAPService
00052 {
00053 public:
00054 BCAPService();
00055 virtual ~BCAPService();
00056
00057 void parseParams();
00058
00059 HRESULT Connect();
00060 HRESULT Disconnect();
00061
00062 HRESULT StartService(ros::NodeHandle& node);
00063 HRESULT StopService();
00064
00065 const std::string& get_Type() const;
00066 void put_Type(const std::string& type);
00067
00068 uint32_t get_Timeout() const;
00069 void put_Timeout(uint32_t value);
00070
00071 unsigned int get_Retry() const;
00072 void put_Retry(unsigned int value);
00073
00074 HRESULT ExecFunction(
00075 int32_t func_id, VARIANT_Vec& vntArgs,
00076 VARIANT_Ptr& vntRet);
00077
00078 private:
00079 bool CallFunction(
00080 bcap::Request &req,
00081 bcap::Response &res);
00082
00083
00084 std::string m_type, m_addr;
00085 int m_port, m_timeout, m_retry, m_wait;
00086
00087
00088 int m_fd;
00089
00090
00091 int m_wdt, m_invoke;
00092
00093
00094 KeyHandle_Vec m_vecKH;
00095
00096
00097 ros::ServiceServer m_svr;
00098 };
00099
00100 }
00101
00102 typedef boost::shared_ptr<bcap_service::BCAPService> BCAPService_Ptr;
00103
00104 #endif