denso_task.cpp
Go to the documentation of this file.
1 
26 
27 namespace denso_robot_core
28 {
29 DensoTask::DensoTask(DensoBase* parent, Service_Vec& service, Handle_Vec& handle, const std::string& name,
30  const int* mode)
31  : DensoBase(parent, service, handle, name, mode)
32 {
33 }
34 
36 {
37 }
38 
40 {
41  return AddVariable(xmlElem);
42 }
43 
45 {
46  DensoVariable_Vec::iterator itVar;
47  for (itVar = m_vecVar.begin(); itVar != m_vecVar.end(); itVar++)
48  {
49  (*itVar)->StartService(node);
50  }
51 
52  m_serving = true;
53 
54  return S_OK;
55 }
56 
58 {
59  m_mtxSrv.lock();
60  m_serving = false;
61  m_mtxSrv.unlock();
62 
63  DensoVariable_Vec::iterator itVar;
64  for (itVar = m_vecVar.begin(); itVar != m_vecVar.end(); itVar++)
65  {
66  (*itVar)->StopService();
67  }
68 
69  return S_OK;
70 }
71 
73 {
74  boost::mutex::scoped_lock lockSrv(m_mtxSrv);
75  if (!m_serving)
76  return false;
77 
78  DensoVariable_Vec::iterator itVar;
79  for (itVar = m_vecVar.begin(); itVar != m_vecVar.end(); itVar++)
80  {
81  (*itVar)->Update();
82  }
83 
84  return true;
85 }
86 
87 HRESULT DensoTask::get_Variable(const std::string& name, DensoVariable_Ptr* var)
88 {
89  if (var == NULL)
90  {
91  return E_INVALIDARG;
92  }
93 
94  DensoBase_Vec vecBase;
95  vecBase.insert(vecBase.end(), m_vecVar.begin(), m_vecVar.end());
96 
97  DensoBase_Ptr pBase;
98  HRESULT hr = DensoBase::get_Object(vecBase, name, &pBase);
99  if (SUCCEEDED(hr))
100  {
101  *var = boost::dynamic_pointer_cast<DensoVariable>(pBase);
102  }
103 
104  return hr;
105 }
106 
107 HRESULT DensoTask::AddVariable(const std::string& name)
108 {
110 }
111 
113 {
114  HRESULT hr = S_OK;
115  XMLElement* xmlVar;
116 
117  for (xmlVar = xmlElem->FirstChildElement(DensoVariable::XML_VARIABLE_NAME); xmlVar != NULL;
119  {
121  if (FAILED(hr))
122  break;
123  }
124 
125  return hr;
126 }
127 
128 } // namespace denso_robot_core
#define ID_TASK_GETVARIABLE
HRESULT get_Variable(const std::string &name, DensoVariable_Ptr *var)
Definition: denso_task.cpp:87
DensoTask(DensoBase *parent, Service_Vec &service, Handle_Vec &handle, const std::string &name, const int *mode)
Definition: denso_task.cpp:29
virtual HRESULT InitializeBCAP()
Definition: denso_base.h:104
DensoVariable_Vec m_vecVar
Definition: denso_task.h:57
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)
#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
const XMLElement * NextSiblingElement(const char *value=0) const
Get the next (right) sibling element of this node, with an optionally supplied name.
Definition: tinyxml2.cpp:824
int32_t HRESULT
HRESULT AddVariable(const std::string &name)
Definition: denso_task.cpp:107
#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:44
const XMLElement * FirstChildElement(const char *value=0) const
Definition: tinyxml2.cpp:796
static constexpr const char * XML_VARIABLE_NAME
std::vector< DensoBase_Ptr > DensoBase_Vec
Definition: denso_base.h:166


denso_robot_core
Author(s): DENSO WAVE INCORPORATED
autogenerated on Sat Feb 18 2023 04:06:02