bcap_service.h
Go to the documentation of this file.
1 
25 #ifndef _BCAP_SERVICE_H_
26 #define _BCAP_SERVICE_H_
27 
28 #include <ros/ros.h>
29 #include <boost/interprocess/smart_ptr/unique_ptr.hpp>
30 
31 #include "variant_allocator.h"
32 #include "bcap_service/bcap.h"
33 #include "bcap_core/dn_common.h"
34 #include "bcap_core/dn_device.h"
35 
36 typedef std::pair<int32_t,uint32_t> KeyHandle;
37 typedef std::vector<KeyHandle> KeyHandle_Vec;
38 
40  void operator()(VARIANT *p) const {
41  VariantClear(p);
42  delete p;
43  }
44 };
45 
46 typedef boost::interprocess::unique_ptr<VARIANT, variant_deleter> VARIANT_Ptr;
47 typedef std::vector<VARIANT, VariantAllocator<VARIANT> > VARIANT_Vec;
48 
49 namespace bcap_service {
50 
52 {
53  public:
54  BCAPService();
55  virtual ~BCAPService();
56 
57  void parseParams();
58 
59  HRESULT Connect();
60  HRESULT Disconnect();
61 
62  HRESULT StartService(ros::NodeHandle& node);
63  HRESULT StopService();
64 
65  const std::string& get_Type() const;
66  void put_Type(const std::string& type);
67 
68  uint32_t get_Timeout() const;
69  void put_Timeout(uint32_t value);
70 
71  unsigned int get_Retry() const;
72  void put_Retry(unsigned int value);
73 
74  HRESULT ExecFunction(
75  int32_t func_id, VARIANT_Vec& vntArgs,
76  VARIANT_Ptr& vntRet);
77 
78  private:
79  bool CallFunction(
80  bcap::Request &req,
81  bcap::Response &res);
82 
83  // Connect parameters
84  std::string m_type, m_addr;
85  int m_port, m_timeout, m_retry, m_wait;
86 
87  // Socket parameters
88  int m_fd;
89 
90  // ServiceStart parameters
91  int m_wdt, m_invoke;
92 
93  // Handle vector
95 
96  // Service
98 };
99 
100 }
101 
103 
104 #endif
unsigned uint32_t
std::vector< VARIANT, VariantAllocator< VARIANT > > VARIANT_Vec
Definition: bcap_service.h:47
void VariantClear(VARIANT *pvarg)
boost::shared_ptr< bcap_service::BCAPService > BCAPService_Ptr
Definition: bcap_service.h:102
std::vector< KeyHandle > KeyHandle_Vec
Definition: bcap_service.h:37
int32_t HRESULT
boost::interprocess::unique_ptr< VARIANT, variant_deleter > VARIANT_Ptr
Definition: bcap_service.h:46
ros::ServiceServer m_svr
Definition: bcap_service.h:97
std::pair< int32_t, uint32_t > KeyHandle
Definition: bcap_service.h:36
int int32_t
void operator()(VARIANT *p) const
Definition: bcap_service.h:40


bcap_service
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:23