denso_task.cpp
Go to the documentation of this file.
1 
26 
27 namespace denso_robot_core {
28 
30  Service_Vec& service, Handle_Vec& handle,
31  const std::string& name, const int* mode)
32  : DensoBase(parent, service, handle, name, mode)
33 {
34 
35 }
36 
38 {
39 
40 }
41 
43 {
44  return AddVariable(xmlElem);
45 }
46 
48 {
49  DensoVariable_Vec::iterator itVar;
50  for(itVar = m_vecVar.begin();
51  itVar != m_vecVar.end();
52  itVar++)
53  {
54  (*itVar)->StartService(node);
55  }
56 
57  m_serving = true;
58 
59  return S_OK;
60 }
61 
63 {
64  m_mtxSrv.lock();
65  m_serving = false;
66  m_mtxSrv.unlock();
67 
68  DensoVariable_Vec::iterator itVar;
69  for(itVar = m_vecVar.begin();
70  itVar != m_vecVar.end();
71  itVar++)
72  {
73  (*itVar)->StopService();
74  }
75 
76  return S_OK;
77 }
78 
80 {
81  boost::mutex::scoped_lock lockSrv(m_mtxSrv);
82  if(!m_serving) return false;
83 
84  DensoVariable_Vec::iterator itVar;
85  for(itVar = m_vecVar.begin();
86  itVar != m_vecVar.end();
87  itVar++)
88  {
89  (*itVar)->Update();
90  }
91 
92  return true;
93 }
94 
95 HRESULT DensoTask::get_Variable(const std::string& name, DensoVariable_Ptr* var)
96 {
97  if(var == NULL) {
98  return E_INVALIDARG;
99  }
100 
101  DensoBase_Vec vecBase;
102  vecBase.insert(vecBase.end(), m_vecVar.begin(), m_vecVar.end());
103 
104  DensoBase_Ptr pBase;
105  HRESULT hr = DensoBase::get_Object(vecBase, name, &pBase);
106  if(SUCCEEDED(hr)) {
107  *var = boost::dynamic_pointer_cast<DensoVariable>(pBase);
108  }
109 
110  return hr;
111 }
112 
113 HRESULT DensoTask::AddVariable(const std::string& name)
114 {
116  name, m_vecVar);
117 }
118 
120 {
121  HRESULT hr = S_OK;
122  XMLElement *xmlVar;
123 
124  for(xmlVar = xmlElem->FirstChildElement(XML_VARIABLE_NAME);
125  xmlVar!= NULL;
126  xmlVar = xmlVar->NextSiblingElement(XML_VARIABLE_NAME))
127  {
129  xmlVar, m_vecVar);
130  if(FAILED(hr)) break;
131  }
132 
133  return hr;
134 }
135 
136 }
#define ID_TASK_GETVARIABLE
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
Definition: denso_task.cpp:95
DensoTask(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
Definition: denso_task.cpp:29
const XMLElement * FirstChildElement(const char *name=0) const
Definition: tinyxml2.cpp:874
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:107
DensoVariable_Vec m_vecVar
Definition: denso_task.h:59
HRESULT AddVariable(int32_t get_id, const std::string &name, std::vector< boost::shared_ptr< class DensoVariable > > &vecVar, int16_t vt=VT_EMPTY, bool bRead=false, bool bWrite=false, bool bID=false, int iDuration=BCAP_VAR_DEFAULT_DURATION)
const XMLElement * NextSiblingElement(const char *name=0) const
Get the next (right) sibling element of this node, with an optionally supplied name.
Definition: tinyxml2.cpp:902
#define S_OK
std::vector< uint32_t > Handle_Vec
Definition: denso_base.h:67
#define FAILED(hr)
#define E_INVALIDARG
std::vector< BCAPService_Ptr > Service_Vec
Definition: denso_base.h:68
int32_t HRESULT
HRESULT AddVariable(const std::string &name)
Definition: denso_task.cpp:113
#define SUCCEEDED(hr)
HRESULT get_Object(const std::vector< boost::shared_ptr< DensoBase > > &vecBase, int index, boost::shared_ptr< DensoBase > *obj)
HRESULT StartService(ros::NodeHandle &node)
Definition: denso_task.cpp:47
#define XML_VARIABLE_NAME
std::vector< DensoBase_Ptr > DensoBase_Vec
Definition: denso_base.h:173


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