denso_base.h
Go to the documentation of this file.
00001 
00025 #ifndef _DENSO_BASE_H_
00026 #define _DENSO_BASE_H_
00027 
00028 #include <ros/ros.h>
00029 #include "bcap_core/bcap_funcid.h"
00030 #include "bcap_service/bcap_service.h"
00031 
00032 // Message (std_msgs)
00033 #include <std_msgs/Int32.h>
00034 #include <std_msgs/Float32.h>
00035 #include <std_msgs/Float64.h>
00036 #include <std_msgs/String.h>
00037 #include <std_msgs/Bool.h>
00038 #include <std_msgs/Float32MultiArray.h>
00039 #include <std_msgs/Float64MultiArray.h>
00040 using namespace std_msgs;
00041 
00042 // Message (original)
00043 #include "denso_robot_core/Joints.h"
00044 #include "denso_robot_core/ExJoints.h"
00045 #include "denso_robot_core/PoseData.h"
00046 #include "denso_robot_core/UserIO.h"
00047 
00048 // Action
00049 #include <actionlib/server/simple_action_server.h>
00050 using namespace actionlib;
00051 
00052 // Action (original)
00053 #include "denso_robot_core/MoveStringAction.h"
00054 #include "denso_robot_core/MoveValueAction.h"
00055 #include "denso_robot_core/DriveStringAction.h"
00056 #include "denso_robot_core/DriveValueAction.h"
00057 
00058 #include "denso_robot_core/tinyxml2.h"
00059 using namespace tinyxml2;
00060 
00061 #define MESSAGE_QUEUE (1)
00062 #define BCAP_VAR_DEFAULT_DURATION (1000) /* [ms] */
00063 
00064 namespace denso_robot_core {
00065 
00066 typedef std::vector<std::string>     Name_Vec;
00067 typedef std::vector<uint32_t>        Handle_Vec;
00068 typedef std::vector<BCAPService_Ptr> Service_Vec;
00069 
00070 class DensoBase
00071 {
00072 public:
00073   enum {
00074     SRV_MIN = 0,
00075     SRV_ACT = SRV_MIN,
00076     SRV_WATCH,
00077     SRV_MAX = SRV_WATCH
00078   };
00079 
00080 public:
00081   static std::string ConvertBSTRToString(const BSTR bstr);
00082   static BSTR ConvertStringToBSTR(const std::string& str);
00083 
00084 public:
00085   DensoBase(const std::string& name, const int* mode)
00086     : m_parent(NULL),
00087       m_name(name), m_mode(mode), m_serving(false)
00088   {
00089 
00090   }
00091 
00092   DensoBase(DensoBase* parent,
00093      Service_Vec& service, Handle_Vec& handle,
00094      const std::string& name, const int* mode)
00095     : m_parent(parent),
00096       m_name(name), m_mode(mode), m_serving(false)
00097   {
00098     m_vecService = service;
00099     m_vecHandle  = handle;
00100   }
00101 
00102   virtual ~DensoBase()
00103   {
00104     StopService();
00105   }
00106 
00107   virtual HRESULT InitializeBCAP()
00108   {
00109     return S_OK;
00110   }
00111 
00112   virtual HRESULT TerminateBCAP()
00113   {
00114     return S_OK;
00115   }
00116 
00117   virtual HRESULT StartService(ros::NodeHandle& node) = 0;
00118 
00119   virtual HRESULT StopService()
00120   {
00121     return S_OK;
00122   }
00123 
00124   virtual bool Update()
00125   {
00126     return true;
00127   }
00128 
00129   const std::string& Name() const
00130   {
00131     return m_name;
00132   }
00133 
00134   std::string RosName() const;
00135 
00136 protected:
00137   HRESULT AddVariable(int32_t get_id,
00138      const std::string& name,
00139      std::vector<boost::shared_ptr<class DensoVariable> >& vecVar,
00140      int16_t vt = VT_EMPTY, bool bRead = false, bool bWrite = false,
00141      bool bID = false, int iDuration = BCAP_VAR_DEFAULT_DURATION);
00142 
00143   HRESULT AddVariable(int32_t get_id,
00144      const XMLElement *xmlVar,
00145      std::vector<boost::shared_ptr<class DensoVariable> >& vecVar);
00146 
00147   HRESULT AddObject(int32_t get_id, const std::string& name,
00148      Handle_Vec& vecHandle);
00149 
00150   HRESULT GetObjectNames(int32_t func_id,
00151      Name_Vec& vecName);
00152 
00153   HRESULT get_Object(const std::vector<boost::shared_ptr<DensoBase> >& vecBase,
00154      int index, boost::shared_ptr<DensoBase> *obj);
00155 
00156   HRESULT get_Object(const std::vector<boost::shared_ptr<DensoBase> >& vecBase,
00157      const std::string& name, boost::shared_ptr<DensoBase> *obj);
00158 
00159 protected:
00160   DensoBase* m_parent;
00161 
00162   Service_Vec m_vecService;
00163   Handle_Vec  m_vecHandle;
00164 
00165   std::string m_name;
00166   const int* m_mode;
00167 
00168   bool m_serving;
00169   boost::mutex  m_mtxSrv;
00170 };
00171 
00172 typedef boost::shared_ptr<DensoBase> DensoBase_Ptr;
00173 typedef std::vector<DensoBase_Ptr> DensoBase_Vec;
00174 
00175 }
00176 
00177 #endif


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Thu Jun 6 2019 21:00:11