stcamera_node.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (C) 2018, OMRON SENTECH. All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  * * Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the names of OMRON SENTECH nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *****************************************************************************/
30 
34 #include <omronsentech_camera/DeviceConnection.h>
35 
37 
38 namespace stcamera
39 {
41 #define CATCH_GIGECALL_ERR() catch(const StApi::CStGenTLErrorException &x) \
42  {\
43  ROS_ERROR("%s %s %d: \n\tGenTL error: %d %s", \
44  __FILE__,__func__,__LINE__, \
45  x.GetError(), x.GetDescription());\
46  return false; \
47  }\
48  catch(GenICam::GenericException &x)\
49  {\
50  ROS_ERROR("%s %s %d: \n\tGenICam error: %s", \
51  __FILE__,__func__,__LINE__, \
52  x.GetDescription());\
53  return false; \
54  }
55 
56 
58  nh_("~"),
59  msg_device_connection_(nh_.advertise<omronsentech_camera::DeviceConnection>(
61  srv_get_device_list_(nh_.advertiseService(
62  std::string(STSRV_G_device_list),
63  &StCameraNode::getDeviceListCallback, this)),
64  srv_get_module_list_(nh_.advertiseService(
65  std::string(STSRV_G_module_list),
66  &StCameraNode::getModuleListCallback, this)),
67  srv_get_sdk_info_(nh_.advertiseService(
68  std::string(STSRV_G_sdk_info),
69  &StCameraNode::getSDKInfoCallback, this)),
70  srv_get_gige_ip_i_(nh_.advertiseService(
71  std::string(STSRV_G_gige_ip),
72  &StCameraNode::getGigEIPCallback, this)),
73  srv_set_gige_ip_i_(nh_.advertiseService(
74  std::string(STSRV_S_gige_ip),
75  &StCameraNode::setGigEIPCallback, this))
76  {
77  init();
78  }
79 
81  nh_(nh),
82  msg_device_connection_(nh_.advertise<omronsentech_camera::DeviceConnection>(
84  srv_get_device_list_(nh_.advertiseService(
85  std::string(STSRV_G_device_list),
87  srv_get_module_list_(nh_.advertiseService(
88  std::string(STSRV_G_module_list),
90  srv_get_sdk_info_(nh_.advertiseService(
91  std::string(STSRV_G_sdk_info),
93  srv_get_gige_ip_i_(nh_.advertiseService(
94  std::string(STSRV_G_gige_ip),
96  srv_set_gige_ip_i_(nh_.advertiseService(
97  std::string(STSRV_S_gige_ip),
99  {
100  init();
101  }
102 
104  {
105  std::lock_guard<std::mutex> lock(mtx_map_camera_);
106 
107  for (MapCameraInterface::iterator it = map_camera_.begin();
108  it != map_camera_.end();)
109  {
110  if (it->second != nullptr)
111  {
112  delete it->second;
113  }
114  it = map_camera_.erase(it);
115  }
116  }
117 
119  {
120  std::vector<std::string> camera_to_connect;
121  param_.loadCameraList(nh_, camera_to_connect);
122 
123  std::string allowed="Allowed camera: ";
124  if (param_.connectAllCamera())
125  {
126  allowed += "all";
127  }
128  else if (param_.connectFirstCameraOnly())
129  {
130  allowed += "First found camera";
131  }
132  else
133  {
134  std::lock_guard<std::mutex> lock(mtx_map_camera_);
135 
136  // connect to certain camera only
137  for (size_t i = 0; i < camera_to_connect.size(); i++)
138  {
139  // set interface to null for the allowed camera:
140  map_camera_[param_.getNamespace(camera_to_connect[i])] = nullptr;
141  allowed += camera_to_connect[i] + " ";
142  }
143  }
144  ROS_DEBUG("Allowed to connect: %s", allowed.c_str());
145 
146  for (uint32_t i = StApi::StSystemVendor_Sentech;
147  i < StApi::StSystemVendor_Count; i++)
148  {
149  StApi::EStSystemVendor_t vendor = (StApi::EStSystemVendor_t)i;
150  try
151  {
152  stapi_systems_.Register(
153  StApi::CreateIStSystem(vendor, StApi::StInterfaceType_All));
154  }
155  catch(const GenICam::GenericException &x)
156  {
157  if (vendor == StApi::StSystemVendor_Sentech)
158  {
159  ROS_ERROR(
160  "%s %s %d: Unable to initialize OMRON SENTECH GenTL Producer: %s",
161  __FILE__,__func__,__LINE__, x.GetDescription());
162  }
163  }
164  }
165 
166  for (size_t i = 0; i < stapi_systems_.GetSize(); i++)
167  {
168  StApi::IStSystem *p_tl = stapi_systems_[i];
169  p_tl->UpdateInterfaceList();
170  }
171 
172  }
173 
175  {
176  size_t count = 0;
177  std::lock_guard<std::mutex> lock(mtx_map_camera_);
178  for (MapCameraInterface::iterator it = map_camera_.begin();
179  it != map_camera_.end(); it++)
180  {
181  StCameraInterface *c = it->second;
182  if (c != nullptr)
183  {
184  // check device availability
185  if (c->deviceIsLost())
186  {
187  MapDeviceConnection::iterator it2 = map_connection_.find(it->first);
188  if (it2 != map_connection_.end())
189  {
190  it2->second.connected = false;
191  it2->second.timestamp = ros::Time::now();
192  msg_device_connection_.publish(it2->second);
193  }
194  map_camera_[it->first] = nullptr;
195  ROS_INFO("Device %s is disconnected.", it2->first.c_str());
196  delete c;
197  }
198  else
199  {
200  count++;
201  }
202  }
203  }
204 
205  bool connect_first_camera_only = param_.connectFirstCameraOnly();
206  if (connect_first_camera_only)
207  {
208  if (count > 0)
209  {
210  return;
211  }
212  }
213  else if (!param_.connectAllCamera())
214  {
215  bool all_connected = true;
216  for (MapCameraInterface::iterator it = map_camera_.begin();
217  it != map_camera_.end(); it++)
218  {
219  if (it->second == nullptr)
220  {
221  all_connected = false;
222  break;
223  }
224  }
225  if (all_connected)
226  {
227  return;
228  }
229  }
230  //else ROS_INFO("Connect to any devices");
231 
232  // search for camera
233  try
234  {
235  std::lock_guard<std::mutex> lock(mtx_update_device_list_);
236  for (size_t i = 0; i < stapi_systems_.GetSize(); i++)
237  {
238  StApi::IStSystem *p_tl = stapi_systems_[i];
239  size_t ifcount = p_tl->GetInterfaceCount();
240  for (size_t j = 0; j < ifcount; j++)
241  {
242  StApi::IStInterface *p_iface = p_tl->GetIStInterface(j);
243  p_iface->UpdateDeviceList();
244 
245  size_t devcount = p_iface->GetDeviceCount();
246  for (size_t k = 0; k < devcount; k++)
247  {
248  if (p_iface->IsDeviceAvailable(k, GenTL::DEVICE_ACCESS_CONTROL))
249  {
250  const StApi::IStDeviceInfo *p_devinfo =
251  p_iface->GetIStDeviceInfo(k);
252  bool init_ok = initializeCamera(p_iface, p_devinfo);
253  if (init_ok && connect_first_camera_only)
254  {
255  return;
256  }
257  //ROS_INFO("connected %d", init_ok);
258  }
259  } // end loop device
260  } // end loop interface
261  } // end loop system
262  }
263  catch(...)
264  {
265  }
266  }
267 
268  bool StCameraNode::initializeCamera(StApi::IStInterface *p_iface,
269  const StApi::IStDeviceInfo *p_devinfo)
270  {
271  if (p_iface == nullptr || p_devinfo == nullptr)
272  {
273  return false;
274  }
275 
276  std::string device_id = std::string(p_devinfo->GetID());
277  std::string device_displayname = std::string(p_devinfo->GetDisplayName());
278  std::string device_userdefinedname = std::string(p_devinfo->GetUserDefinedName() );
279  std::string key = "";
281  {
282  key = param_.getNamespace(device_id);
283  }
284  else
285  {
286  bool found = false;
287  for (MapCameraInterface::iterator it = map_camera_.begin();
288  it != map_camera_.end(); it++)
289  {
290  key = param_.getNamespace(device_id);
291  if (it->first.compare(key) == 0)
292  {
293  found = true;
294  break;
295  }
296  key = param_.getNamespace(device_displayname);
297  if (it->first.compare(key) == 0)
298  {
299  found = true;
300  break;
301  }
302  key = param_.getNamespace(device_userdefinedname);
303  if (it->first.compare(key) == 0)
304  {
305  found = true;
306  break;
307  }
308  }
309  if (!found) key = "";
310  }
311 
312  if (key.empty())
313  {
314  return false;
315  }
316 
317  try
318  {
319  StApi::IStDeviceReleasable *dev = p_iface->CreateIStDevice(
320  GenICam::gcstring(device_id.c_str()),
321  GenTL::DEVICE_ACCESS_CONTROL);
322 
323  if (p_devinfo->GetTLType().compare(TLTypeU3VName) == 0)
324  {
326  dev, nh_, key, &param_);
327  map_camera_[key] = pu3v;
328  }
329  else if (p_devinfo->GetTLType().compare(TLTypeGEVName) == 0)
330  {
332  dev, nh_, key, &param_);
333  map_camera_[key] = pgev;
334  }
335  else
336  {
338  dev, nh_, key, &param_);
339  map_camera_[key] = pcif;
340  }
341 
342  // store and publish connection msg
343  omronsentech_camera::DeviceConnection msg =
344  fillDeviceConnectionData(dev->GetIStInterface()->GetIStSystem()
345  ->GetIStSystemInfo(), dev->GetIStInterface(),
346  dev->GetIStDeviceInfo(), key, true);
347 
348  map_connection_[key] = msg;
349 
351 
352  ROS_INFO("%s %s %d: %s (%s) is successfully initialized as %s",
353  __FILE__,__func__,__LINE__,
354  device_id.c_str(), device_displayname.c_str(), key.c_str());
355  return true;
356  }
357  catch(GenICam::GenericException &x)
358  {
359  ROS_ERROR("%s %s %d: Unable to open device %s (%s): %s",
360  __FILE__,__func__,__LINE__, device_id.c_str(),
361  device_displayname.c_str(), x.GetDescription());
362  }
363  return false;
364  }
365 
367  omronsentech_camera::GetDeviceList::Request &req,
368  omronsentech_camera::GetDeviceList::Response &res)
369  {
370  std::lock_guard<std::mutex> lock(mtx_update_device_list_);
371  try
372  {
373  for (size_t i = 0; i < stapi_systems_.GetSize(); i++)
374  {
375  StApi::IStSystem *p_tl = stapi_systems_[i];
376  size_t ifcount = p_tl->GetInterfaceCount();
377  for (size_t j = 0; j < ifcount; j++)
378  {
379  StApi::IStInterface *p_iface = p_tl->GetIStInterface(j);
380  p_iface->UpdateDeviceList();
381  size_t devcount = p_iface->GetDeviceCount();
382  for (size_t k = 0; k < devcount; k++)
383  {
384  const StApi::IStDeviceInfo *p_devinfo =
385  p_iface->GetIStDeviceInfo(k);
386  std::string device_id = std::string(p_devinfo->GetID());
387  std::string device_sn = std::string(p_devinfo->GetDisplayName());
388  std::string key_id = param_.getNamespace(device_id);
389  std::string key_sn = param_.getNamespace(device_sn);
390  MapDeviceConnection::iterator it = map_connection_.find(key_id);
391  if (it == map_connection_.end())
392  {
393  it = map_connection_.find(key_sn);
394  }
395  if (it != map_connection_.end())
396  {
397  res.device_list.push_back(it->second);
398  continue;
399  }
400  omronsentech_camera::DeviceConnection msg =
401  fillDeviceConnectionData(p_tl->GetIStSystemInfo(), p_iface,
402  p_devinfo);
403  res.device_list.push_back(msg);
404  } // end loop device
405  } // end loop interface
406  } // end loop system
407  }
408  catch(...)
409  {
410  }
411  return true;
412  }
413 
414 
416  omronsentech_camera::GetModuleList::Request &req,
417  omronsentech_camera::GetModuleList::Response &res)
418  {
419  res.module_name_list.push_back("System");
420  res.module_name_list.push_back("Interface");
421  res.module_name_list.push_back("LocalDevice");
422  res.module_name_list.push_back("RemoteDevice");
423  res.module_name_list.push_back("DataStream");
424  //"StreamBuffer" is not included.
425  return true;
426  }
427 
428 
430  omronsentech_camera::GetSDKInfo::Request &req,
431  omronsentech_camera::GetSDKInfo::Response &res)
432  {
433  res.sdk_version = StApi::GetStApiVersionText();
434 
435  for (size_t i = 0; i < stapi_systems_.GetSize(); i++)
436  {
437  omronsentech_camera::GenTLInfo data;
438  const StApi::IStSystemInfo *info =
439  stapi_systems_[i]->GetIStSystemInfo();
440  char gentl_ver[8];
441  snprintf(gentl_ver,8,"%d.%d", info->GetGenTLVersionMajor(),
442  info->GetGenTLVersionMinor());
443  data.vendor = info->GetVendor();
444  data.version = gentl_ver;
445  data.producer_version = info->GetVersion();
446  data.tltype = info->GetTLType();
447  data.full_path = info->GetPathName();
448  res.gentl_info_list.push_back(data);
449  }
450  return true;
451  }
452 
454  omronsentech_camera::GetGigEIPi::Request &req,
455  omronsentech_camera::GetGigEIPi::Response &res)
456  {
457  try
458  {
459  for (size_t i = 0; i < stapi_systems_.GetSize();i++)
460  {
461  StApi::IStSystem *p_tl = stapi_systems_[i];
462  for (size_t j = 0; j < p_tl->GetInterfaceCount(); j++)
463  {
464  StApi::IStInterface *p_iface = p_tl->GetIStInterface(j);
465  if (p_iface->GetIStInterfaceInfo()->GetTLType()
466  .compare(TLTypeGEVName) != 0)
467  {
468  continue;
469  }
470 
471  p_iface->UpdateDeviceList();
472  GenApi::CNodeMapPtr p_nodemap(p_iface->GetIStPort()->GetINodeMap());
473  GenApi::CIntegerPtr p_integer_ip(
474  p_nodemap->GetNode("GevInterfaceSubnetIPAddress"));
475  GenApi::CIntegerPtr p_integer_subnet(
476  p_nodemap->GetNode("GevInterfaceSubnetMask"));
477  GenApi::CIntegerPtr p_integer_gw(
478  p_nodemap->GetNode("GevInterfaceGateway"));
479  res.if_ip_address = p_integer_ip->ToString();
480  res.if_ip_mask = p_integer_subnet->ToString();
481  res.if_ip_gateway = p_integer_gw->ToString();
482 
483  GenApi::CIntegerPtr pDeviceSelector(
484  p_nodemap->GetNode("DeviceSelector"));
485  const int64_t nMaxIndex = pDeviceSelector->GetMax();
486  for (int64_t k = 0; k <= nMaxIndex; k++)
487  {
488  pDeviceSelector->SetValue(k);
489  GenApi::CStringPtr pIStringDeviceID(p_nodemap->GetNode("DeviceID"));
490  GenICam::gcstring strDeviceID = pIStringDeviceID->GetValue();
491 
492  if (strDeviceID.compare(req.camera_id.c_str()) != 0)
493  {
494  continue;
495  }
496  GenApi::CIntegerPtr p_integer_ip(
497  p_nodemap->GetNode("GevDeviceIPAddress"));
498  GenApi::CIntegerPtr p_integer_subnet(
499  p_nodemap->GetNode("GevDeviceSubnetMask"));
500  GenApi::CIntegerPtr p_integer_gw(
501  p_nodemap->GetNode("GevDeviceGateway"));
502  res.dev_ip_address = p_integer_ip->ToString();
503  res.dev_ip_mask = p_integer_subnet->ToString();
504  res.dev_ip_gateway = p_integer_gw->ToString();
505  return true;
506  } // end loop device
507  } // end loop interface
508  } // end loop system
509  ROS_ERROR("The Camera with the given ID %s could not be found.",
510  req.camera_id.c_str());
511  }
513  return false;
514  }
515 
517  omronsentech_camera::SetGigEIPi::Request &req,
518  omronsentech_camera::SetGigEIPi::Response &res)
519  {
520  try
521  {
522  for (size_t i = 0; i < stapi_systems_.GetSize();i++)
523  {
524  StApi::IStSystem *p_tl = stapi_systems_[i];
525  for (size_t j = 0; j < p_tl->GetInterfaceCount(); j++)
526  {
527  StApi::IStInterface *p_iface = p_tl->GetIStInterface(j);
528  if (p_iface->GetIStInterfaceInfo()->GetTLType()
529  .compare(TLTypeGEVName) != 0)
530  {
531  continue;
532  }
533 
534  p_iface->UpdateDeviceList();
535  GenApi::CNodeMapPtr p_nodemap(p_iface->GetIStPort()->GetINodeMap());
536  GenApi::CIntegerPtr pDeviceSelector(
537  p_nodemap->GetNode("DeviceSelector"));
538  const int64_t nMaxIndex = pDeviceSelector->GetMax();
539  for (int64_t k = 0; k <= nMaxIndex; k++)
540  {
541  pDeviceSelector->SetValue(k);
542  GenApi::CStringPtr pIStringDeviceID(p_nodemap->GetNode("DeviceID"));
543  GenICam::gcstring strDeviceID = pIStringDeviceID->GetValue();
544 
545  if (strDeviceID.compare(req.camera_id.c_str()) != 0)
546  {
547  continue;
548  }
549 
550  GenApi::CIntegerPtr p_integer_ip(
551  p_nodemap->GetNode("GevDeviceForceIPAddress"));
552  GenApi::CIntegerPtr p_integer_subnet(
553  p_nodemap->GetNode("GevDeviceForceSubnetMask"));
554  GenApi::CIntegerPtr p_integer_gw(
555  p_nodemap->GetNode("GevDeviceForceGateway"));
556  GenApi::CCommandPtr pCommand(
557  p_nodemap->GetNode("GevDeviceForceIP"));
558 
559  p_integer_ip->SetValue(ntohl(inet_addr(req.ip_address.c_str())));
560  p_integer_subnet->SetValue(ntohl(inet_addr(req.ip_mask.c_str())));
561  p_integer_gw->SetValue(ntohl(inet_addr(req.ip_gateway.c_str())));
562  pCommand->Execute();
563  return true;
564  } // end loop device
565  } // end loop interface
566  } // end loop system
567  ROS_ERROR("The Camera with the given ID %s could not be found.",
568  req.camera_id.c_str());
569  }
571  return false;
572  }
573 
574  omronsentech_camera::DeviceConnection StCameraNode::fillDeviceConnectionData(
575  const StApi::IStSystemInfo *p_tlinfo, StApi::IStInterface* p_iface,
576  const StApi::IStDeviceInfo *p_devinfo, std::string device_namespace,
577  bool connected)
578  {
579  omronsentech_camera::DeviceConnection msg;
580 
581  msg.timestamp = ros::Time::now();
582  msg.device_id = p_devinfo->GetID().c_str();
583  msg.device_model = p_devinfo->GetModel().c_str();
584  msg.device_serial = p_devinfo->GetSerialNumber().c_str();
585  msg.device_namespace = device_namespace;
586  msg.device_tltype = p_devinfo->GetTLType().c_str();
587 
588  if (msg.device_tltype.compare(TLTypeGEVName) == 0)
589  {
590  try
591  {
592  GenApi::CNodeMapPtr p_nodemap(p_iface->GetIStPort()->GetINodeMap());
593  GenApi::CIntegerPtr p_integer_ip(
594  p_nodemap->GetNode("GevInterfaceSubnetIPAddress"));
595  GenApi::CIntegerPtr p_integer_subnet(
596  p_nodemap->GetNode("GevInterfaceSubnetMask"));
597  GenApi::CIntegerPtr p_integer_gw(
598  p_nodemap->GetNode("GevInterfaceGateway"));
599  msg.device_tl_specific_field.push_back("if_ip_address");
600  msg.device_tl_specific_value.push_back(
601  p_integer_ip->ToString().c_str());
602  msg.device_tl_specific_field.push_back("if_ip_mask");
603  msg.device_tl_specific_value.
604  push_back(p_integer_subnet->ToString().c_str());
605  msg.device_tl_specific_field.push_back("if_ip_gateway");
606  msg.device_tl_specific_value.push_back(
607  p_integer_gw->ToString().c_str());
608 
609  GenApi::CIntegerPtr pDeviceSelector(
610  p_nodemap->GetNode("DeviceSelector"));
611  const int64_t nMaxIndex = pDeviceSelector->GetMax();
612  for (int64_t k = 0; k <= nMaxIndex; k++)
613  {
614  pDeviceSelector->SetValue(k);
615  GenApi::CStringPtr pIStringDeviceID(p_nodemap->GetNode("DeviceID"));
616  GenICam::gcstring strDeviceID = pIStringDeviceID->GetValue();
617 
618  if (strDeviceID.compare(msg.device_id.c_str()) != 0)
619  {
620  continue;
621  }
622  GenApi::CIntegerPtr p_integer_ip(
623  p_nodemap->GetNode("GevDeviceIPAddress"));
624  GenApi::CIntegerPtr p_integer_subnet(
625  p_nodemap->GetNode("GevDeviceSubnetMask"));
626  GenApi::CIntegerPtr p_integer_gw(
627  p_nodemap->GetNode("GevDeviceGateway"));
628  msg.device_tl_specific_field.push_back("dev_ip_address");
629  msg.device_tl_specific_value.
630  push_back(p_integer_ip->ToString().c_str());
631  msg.device_tl_specific_field.push_back("dev_ip_mask");
632  msg.device_tl_specific_value.
633  push_back(p_integer_subnet->ToString().c_str());
634  msg.device_tl_specific_field.push_back("dev_ip_gateway");
635  msg.device_tl_specific_value.
636  push_back(p_integer_gw->ToString().c_str());
637  break;
638  }
639  }
640  catch(...)
641  {
642  }
643  }
644  msg.connected = connected;
645 
646  // gentl info
647  char gentl_ver[8];
648  snprintf(gentl_ver,8,"%d.%d", p_tlinfo->GetGenTLVersionMajor(),
649  p_tlinfo->GetGenTLVersionMinor());
650  msg.device_gentl_info.vendor = p_tlinfo->GetVendor();
651  msg.device_gentl_info.version = gentl_ver;
652  msg.device_gentl_info.producer_version = p_tlinfo->GetVersion();
653  msg.device_gentl_info.tltype = p_tlinfo->GetTLType();
654  msg.device_gentl_info.full_path = p_tlinfo->GetPathName();
655 
656  return msg;
657  }
658 
659 } // end of namespace stcamera
bool getSDKInfoCallback(omronsentech_camera::GetSDKInfo::Request &req, omronsentech_camera::GetSDKInfo::Response &res)
Class to control a connected GigEVision camera.
#define STSRV_G_sdk_info
Definition: stheader.h:144
ros::Publisher msg_device_connection_
ros::ServiceServer srv_get_gige_ip_i_
bool getModuleListCallback(omronsentech_camera::GetModuleList::Request &req, omronsentech_camera::GetModuleList::Response &res)
Class to control a connected GigEVision camera.
ros::NodeHandle nh_
bool setGigEIPCallback(omronsentech_camera::SetGigEIPi::Request &req, omronsentech_camera::SetGigEIPi::Response &res)
Class implementation for stcamera_node.
Definition: stcamera_node.h:64
Class to control a connected USB3Vision camera.
#define STSRV_S_gige_ip
Definition: stheader.h:150
bool getGigEIPCallback(omronsentech_camera::GetGigEIPi::Request &req, omronsentech_camera::GetGigEIPi::Response &res)
bool initializeCamera(StApi::IStInterface *p_iface, const StApi::IStDeviceInfo *p_devinfo)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_INFO(...)
#define STCAMERA_QUEUE_SIZE
Definition: stheader.h:41
MapCameraInterface map_camera_
Contains definitions and macros.
StApi::CIStSystemPtrArray stapi_systems_
ros::ServiceServer srv_get_sdk_info_
void loadCameraList(const ros::NodeHandle &nh, std::vector< std::string > &camera_to_connect)
Definition: stparameter.cpp:43
Base class to control a connected camera.
Class implementation for stcamera_node.
bool getDeviceListCallback(omronsentech_camera::GetDeviceList::Request &req, omronsentech_camera::GetDeviceList::Response &res)
MapDeviceConnection map_connection_
#define STSRV_G_gige_ip
Definition: stheader.h:147
std::string getNamespace(std::string camera_id)
std::mutex mtx_update_device_list_
static Time now()
#define STSRV_G_module_list
Definition: stheader.h:141
ros::ServiceServer srv_get_device_list_
omronsentech_camera::DeviceConnection fillDeviceConnectionData(const StApi::IStSystemInfo *p_tlinfo, StApi::IStInterface *p_iface, const StApi::IStDeviceInfo *p_devinfo, std::string device_namespace="", bool connected=false)
#define CATCH_GIGECALL_ERR()
#define STMSG_device_connection
Definition: stheader.h:115
#define STSRV_G_device_list
Definition: stheader.h:135
ros::ServiceServer srv_set_gige_ip_i_
ros::ServiceServer srv_get_module_list_
#define ROS_ERROR(...)
Class to control a connected GigEVision camera.
#define ROS_DEBUG(...)


omronsentech_camera
Author(s): OSE ROS Support
autogenerated on Tue Jun 28 2022 02:27:35