denso_base.h
Go to the documentation of this file.
1 
25 #ifndef _DENSO_BASE_H_
26 #define _DENSO_BASE_H_
27 
28 #include <ros/ros.h>
29 #include "bcap_core/bcap_funcid.h"
31 
32 // Message (std_msgs)
33 #include <std_msgs/Int32.h>
34 #include <std_msgs/Float32.h>
35 #include <std_msgs/Float64.h>
36 #include <std_msgs/String.h>
37 #include <std_msgs/Bool.h>
38 #include <std_msgs/Float32MultiArray.h>
39 #include <std_msgs/Float64MultiArray.h>
40 using namespace std_msgs;
41 
42 // Message (original)
43 #include "denso_robot_core/Joints.h"
44 #include "denso_robot_core/ExJoints.h"
45 #include "denso_robot_core/PoseData.h"
46 #include "denso_robot_core/UserIO.h"
47 
48 // Action
50 using namespace actionlib;
51 
52 // Action (original)
53 #include "denso_robot_core/MoveStringAction.h"
54 #include "denso_robot_core/MoveValueAction.h"
55 #include "denso_robot_core/DriveStringAction.h"
56 #include "denso_robot_core/DriveValueAction.h"
57 
59 using namespace tinyxml2;
60 
61 #define MESSAGE_QUEUE (1)
62 #define BCAP_VAR_DEFAULT_DURATION (1000) /* [ms] */
63 
64 namespace denso_robot_core {
65 
66 typedef std::vector<std::string> Name_Vec;
67 typedef std::vector<uint32_t> Handle_Vec;
68 typedef std::vector<BCAPService_Ptr> Service_Vec;
69 
70 class DensoBase
71 {
72 public:
73  enum {
74  SRV_MIN = 0,
75  SRV_ACT = SRV_MIN,
77  SRV_MAX = SRV_WATCH
78  };
79 
80 public:
81  static std::string ConvertBSTRToString(const BSTR bstr);
82  static BSTR ConvertStringToBSTR(const std::string& str);
83 
84 public:
85  DensoBase(const std::string& name, const int* mode)
86  : m_parent(NULL),
87  m_name(name), m_mode(mode), m_serving(false)
88  {
89 
90  }
91 
93  Service_Vec& service, Handle_Vec& handle,
94  const std::string& name, const int* mode)
95  : m_parent(parent),
96  m_name(name), m_mode(mode), m_serving(false)
97  {
98  m_vecService = service;
99  m_vecHandle = handle;
100  }
101 
102  virtual ~DensoBase()
103  {
104  StopService();
105  }
106 
108  {
109  return S_OK;
110  }
111 
113  {
114  return S_OK;
115  }
116 
117  virtual HRESULT StartService(ros::NodeHandle& node) = 0;
118 
120  {
121  return S_OK;
122  }
123 
124  virtual bool Update()
125  {
126  return true;
127  }
128 
129  const std::string& Name() const
130  {
131  return m_name;
132  }
133 
134  std::string RosName() const;
135 
136 protected:
137  HRESULT AddVariable(int32_t get_id,
138  const std::string& name,
139  std::vector<boost::shared_ptr<class DensoVariable> >& vecVar,
140  int16_t vt = VT_EMPTY, bool bRead = false, bool bWrite = false,
141  bool bID = false, int iDuration = BCAP_VAR_DEFAULT_DURATION);
142 
143  HRESULT AddVariable(int32_t get_id,
144  const XMLElement *xmlVar,
145  std::vector<boost::shared_ptr<class DensoVariable> >& vecVar);
146 
147  HRESULT AddObject(int32_t get_id, const std::string& name,
148  Handle_Vec& vecHandle);
149 
150  HRESULT GetObjectNames(int32_t func_id,
151  Name_Vec& vecName);
152 
153  HRESULT get_Object(const std::vector<boost::shared_ptr<DensoBase> >& vecBase,
154  int index, boost::shared_ptr<DensoBase> *obj);
155 
156  HRESULT get_Object(const std::vector<boost::shared_ptr<DensoBase> >& vecBase,
157  const std::string& name, boost::shared_ptr<DensoBase> *obj);
158 
159 protected:
161 
162  Service_Vec m_vecService;
163  Handle_Vec m_vecHandle;
164 
165  std::string m_name;
166  const int* m_mode;
167 
168  bool m_serving;
169  boost::mutex m_mtxSrv;
170 };
171 
173 typedef std::vector<DensoBase_Ptr> DensoBase_Vec;
174 
175 }
176 
177 #endif
short int16_t
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:107
#define S_OK
wchar_t * BSTR
std::vector< uint32_t > Handle_Vec
Definition: denso_base.h:67
VT_EMPTY
virtual HRESULT TerminateBCAP()
Definition: denso_base.h:112
std::vector< BCAPService_Ptr > Service_Vec
Definition: denso_base.h:68
int32_t HRESULT
std::vector< std::string > Name_Vec
Definition: denso_base.h:66
int int32_t
boost::shared_ptr< DensoBase > DensoBase_Ptr
Definition: denso_base.h:172
std::vector< DensoBase_Ptr > DensoBase_Vec
Definition: denso_base.h:173
DensoBase(const std::string &name, const int *mode)
Definition: denso_base.h:85
virtual HRESULT StopService()
Definition: denso_base.h:119
#define BCAP_VAR_DEFAULT_DURATION
Definition: denso_base.h:62
const std::string & Name() const
Definition: denso_base.h:129
DensoBase(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
Definition: denso_base.h:92


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