stcamera_interface.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (C) 2018, OMRON SENTECH. All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the names of OMRON SENTECH nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *****************************************************************************/
29 
31 #include <omronsentech_camera/ElementFloat64.h>
32 #include <omronsentech_camera/ElementInt64.h>
33 #include <omronsentech_camera/ElementBool.h>
34 #include <omronsentech_camera/ElementString.h>
35 #include <omronsentech_camera/GenICamEvent.h>
36 #include <sensor_msgs/CameraInfo.h>
37 
38 namespace stcamera
39 {
40 
42  StApi::IStDeviceReleasable *dev,
43  ros::NodeHandle nh_parent,
44  const std::string &camera_namespace,
45  StParameter *param,
46  uint32_t queue_size):
47  camera_namespace_(camera_namespace),
48  tl_dev_(dev),
49  nh_(nh_parent, camera_namespace_),
50  param_(param),
51  it_(nh_),
52  cinfo_(nh_),
53  msg_chunk_(nh_.advertise<omronsentech_camera::Chunk>(
54  std::string(STMSG_chunk), queue_size)),
55  queue_size_(queue_size),
56  it_campub_(it_.advertiseCamera(std::string(STMSG_image), queue_size)),
57  srv_read_node_(nh_.advertiseService(std::string(STSRV_R_node),
58  &StCameraInterface::readNodeCallback, this)),
59  srv_read_node_bool_(nh_.advertiseService(
60  std::string(STSRV_R_node_bool),
61  &StCameraInterface::readNodeBoolCallback, this)),
62  srv_read_node_enum_(nh_.advertiseService(
63  std::string(STSRV_R_node_enum),
64  &StCameraInterface::readNodeEnumCallback, this)),
65  srv_read_node_int_(nh_.advertiseService(
66  std::string(STSRV_R_node_int),
67  &StCameraInterface::readNodeIntCallback, this)),
68  srv_read_node_float_(nh_.advertiseService(
69  std::string(STSRV_R_node_float),
70  &StCameraInterface::readNodeFloatCallback, this)),
71  srv_read_node_string_(nh_.advertiseService(
72  std::string(STSRV_R_node_string),
73  &StCameraInterface::readNodeStringCallback, this)),
74  srv_write_node_(nh_.advertiseService(
75  std::string(STSRV_W_node),
76  &StCameraInterface::writeNodeCallback, this)),
77  srv_write_node_bool_(nh_.advertiseService(
78  std::string(STSRV_W_node_bool),
79  &StCameraInterface::writeNodeBoolCallback, this)),
80  srv_write_node_enum_int_(nh_.advertiseService(
81  std::string(STSRV_W_node_enum_int),
82  &StCameraInterface::writeNodeEnumIntCallback, this)),
83  srv_write_node_enum_str_(nh_.advertiseService(
84  std::string(STSRV_W_node_enum_str),
85  &StCameraInterface::writeNodeEnumStrCallback, this)),
86  srv_write_node_int_(nh_.advertiseService(
87  std::string(STSRV_W_node_int),
88  &StCameraInterface::writeNodeIntCallback, this)),
89  srv_write_node_float_(nh_.advertiseService(
90  std::string(STSRV_W_node_float),
91  &StCameraInterface::writeNodeFloatCallback, this)),
92  srv_write_node_string_(nh_.advertiseService(
93  std::string(STSRV_W_node_string),
94  &StCameraInterface::writeNodeStringCallback, this)),
95  srv_execute_node_(nh_.advertiseService(
96  std::string(STSRV_W_node_command),
97  &StCameraInterface::executeNodeCallback, this)),
98  srv_enable_chunk_(nh_.advertiseService(
99  std::string(STSRV_E_chunk),
100  &StCameraInterface::enableChunkCallback, this)),
101  srv_enable_trigger_(nh_.advertiseService(
102  std::string(STSRV_E_trigger),
103  &StCameraInterface::enableTriggerCallback, this)),
104  srv_enable_event_node_(nh_.advertiseService(
105  std::string(STSRV_E_event_node),
106  &StCameraInterface::enableEventNodeCallback, this)),
107  srv_enable_image_acquisition_(nh_.advertiseService(
108  std::string(STSRV_E_image_acquisition),
109  &StCameraInterface::enableImageAcquisitionCallback, this)),
110  srv_enable_event_acquisition_(nh_.advertiseService(
111  std::string(STSRV_E_event_acquisition),
112  &StCameraInterface::enableEventAcquisitionCallback, this)),
113  srv_get_image_acquisition_status_(nh_.advertiseService(
115  &StCameraInterface::getImageAcquisitionStatusCallback, this)),
116  srv_get_event_acquisition_status_list_(nh_.advertiseService(
118  &StCameraInterface::getEventAcquisitionStatusListCallback, this)),
119  srv_get_event_node_status_list_(nh_.advertiseService(
121  &StCameraInterface::getEventNodeStatusListCallback, this)),
122  srv_get_chunk_list_(nh_.advertiseService(
123  std::string(STSRV_G_chunk_list),
124  &StCameraInterface::getChunkListCallback, this)),
125  srv_get_trigger_list_(nh_.advertiseService(
126  std::string(STSRV_G_trigger_list),
127  &StCameraInterface::getTriggerListCallback, this)),
128  srv_get_enum_list_(nh_.advertiseService(
129  std::string(STSRV_G_enum_list),
130  &StCameraInterface::getEnumListCallback, this)),
131  srv_get_genicam_node_info_(nh_.advertiseService(
132  std::string(STSRV_G_genicam_node_info),
133  &StCameraInterface::getGenICamNodeInfoCallback, this)),
134  srv_send_soft_trigger_(nh_.advertiseService(
135  std::string(STSRV_send_soft_trigger),
136  &StCameraInterface::sendSoftTriggerCallback, this)),
137  srv_get_last_error_(nh_.advertiseService(
138  std::string(STSRV_G_last_error),
139  &StCameraInterface::getLastErrorCallback, this)),
140  bool_event_system_(false),
141  bool_event_interface_(false),
142  bool_event_device_(false),
143  bool_event_datastream_(false),
144  last_error_(0),
145  destroyed_(false)
146  {
147  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
148  std::lock_guard<std::mutex> lock2(mtx_event_);
149  std::lock_guard<std::mutex> lock3(mtx_chunk_);
150 
151  // initialize default_event
152  std::string default_event = STMSG_event;
153  map_msg_event_.insert(std::pair<std::string, ros::Publisher>(
154  default_event,
155  nh_.advertise<omronsentech_camera::Event>(default_event, queue_size)));
156 
157  // initialize Data stream and register acquisition callback
158  tl_ds_.Reset(tl_dev_->CreateIStDataStream(0));
159  StApi::RegisterCallback(tl_ds_, *this,
161 
162  // register event callback for GenTL modules Device, Interface, and System
163  StApi::RegisterCallback(tl_dev_, *this,
165  (void *)NULL);
166  StApi::RegisterCallback(tl_dev_->GetIStInterface(), *this,
168  (void *)NULL);
169  StApi::RegisterCallback(tl_dev_->GetIStInterface()->GetIStSystem(), *this,
171  (void *)NULL);
172 
173  // register device lost
174  if (tl_dev_->GetIStInterface()->GetIStSystem()->GetStSystemVendor() ==
175  StApi::StSystemVendor_Sentech)
176  {
177  struct StCallback stc;
178  stc.topic_name_ = default_event;
179 
180  std::string callback_node = "EventDeviceLost";
181  GenApi::CNodeMapPtr p(tl_dev_->GetLocalIStPort()->GetINodeMap());
182  GenApi::CNodePtr node_callback(p->GetNode(
183  GenICam::gcstring(callback_node.c_str())));
184  stc.cb_ = StApi::RegisterCallback(node_callback, *this,
186  (void*)(&map_event_localdevice_), GenApi::cbPostInsideLock);
187  GenApi::CEnumerationPtr p_event_selector(p->GetNode(
188  GenICam::gcstring("EventSelector")));
189  GenApi::CEnumEntryPtr p_event_selector_entry(
190  p_event_selector->GetEntryByName(GenICam::gcstring("DeviceLost")));
191  p_event_selector->SetIntValue(p_event_selector_entry->GetValue());
192  GenApi::CEnumerationPtr p_event_notif(p->GetNode(
193  GenICam::gcstring("EventNotification")));
194  GenApi::CEnumEntryPtr p_event_notif_entry(
195  p_event_notif->GetEntryByName(GenICam::gcstring("On")));
196  p_event_notif->SetIntValue(p_event_notif_entry->GetValue());
197  tl_dev_->StartEventAcquisitionThread();
198  map_event_localdevice_[callback_node] = stc;
199  bool_event_device_ = true;
200  }
201 
202  // check if chunk is enabled.
203  try
204  {
205  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
206  GenApi::INode *node_sel = mp->GetNode( GenICam::gcstring("ChunkSelector"));
207  GenApi::INode *node_enable = mp->GetNode(GenICam::gcstring("ChunkEnable"));
208  GenApi::INode *node_chunk_active = mp->GetNode(
209  GenICam::gcstring("ChunkModeActive"));
210  if (node_sel && node_enable && node_chunk_active)
211  {
212  GenApi::CBooleanPtr chunk_active(node_chunk_active);
213  GenApi::CEnumerationPtr chunk_selector(node_sel);
214  GenApi::NodeList_t nodelist;
215  bool revert_chunk_mode = (false == chunk_active->GetValue());
216  if (revert_chunk_mode)
217  {
218  chunk_active->SetValue(true);
219  }
220  chunk_selector->GetEntries(nodelist);
221  for (GenApi::NodeList_t::iterator it = nodelist.begin();
222  it != nodelist.end(); it++)
223  {
224  if (GenApi::IsAvailable(*it))
225  {
226  GenApi::CEnumEntryPtr enum_entry(*it);
227  std::string chunk_name = enum_entry->GetSymbolic().c_str();
228  chunk_selector->SetIntValue(enum_entry->GetValue());
229  GenApi::CBooleanPtr chunk_enable(node_enable);
230  if (GenApi::IsReadable(chunk_enable) &&
231  chunk_enable->GetValue() == true)
232  {
233  GenICam::gcstring chunk_value_name("Chunk");
234  chunk_value_name.append(chunk_name.c_str());
235  GenApi::CNodePtr p_chunk_value(mp->GetNode(
236  GenICam::gcstring(chunk_value_name)));
237  if (!p_chunk_value) continue;
238  MapChunk::iterator itm = map_chunk_.find(p_chunk_value
239  ->GetName().c_str());
240  if (itm == map_chunk_.end() || itm->second == nullptr)
241  {
242  map_chunk_[p_chunk_value->GetName().c_str()] = p_chunk_value;
243  }
244  }
245  }
246  }
247  if (revert_chunk_mode)
248  {
249  chunk_active->SetValue(false);
250  }
251  }
252  }
253  catch(GenICam::GenericException &x)
254  {
255  ROS_ERROR("%s %s %d: \n\t%s GenICam error when checking chunk: %s",
256  __FILE__,__func__,__LINE__,
257  camera_namespace_.c_str(), x.GetDescription());
258  }
259 
261 
262  // start acquisition
264  tl_ds_->StartAcquisition();
265  tl_dev_->AcquisitionStart();
266  }
267 
269  {
270  ROS_INFO("Closing device %s", camera_namespace_.c_str());
271  destroyed_ = true;
272  std::lock_guard<std::mutex> lock(mtx_event_);
273  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
274 
275  // Deregister all node callback
276  MapCallback *cblist[5] =
277  {
283  };
284  for (int i = 0; i < 5; i++)
285  {
286  MapCallback *cb = cblist[i];
287  for (MapCallback::iterator it = cb->begin(); it != cb->end(); it++)
288  {
289  StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
290  cbf->Release();
291  }
292  cb->clear();
293  }
294 
295  map_msg_event_.clear();
296 
297  if (!tl_dev_->IsDeviceLost())
298  {
300  {
301  tl_dev_->AcquisitionStop();
302  tl_ds_->StopAcquisition();
304  }
305  }
306  tl_ds_.Reset(nullptr);
307  tl_dev_.Reset(nullptr);
308  ROS_INFO("Closing device %s done.", camera_namespace_.c_str());
309  }
310 
311 
313  {
314  return (tl_dev_->IsDeviceLost());
315  }
316 
317 
318  void StCameraInterface::eventSystemCB(StApi::IStCallbackParamBase *p,
319  void *pvContext)
320  {
321  if (destroyed_) return;
322  omronsentech_camera::Event msg;
323  msg.timestamp = ros::Time::now();
324  msg.module_name = "System";
325  if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_SystemError)
326  {
327  StApi::IStCallbackParamGenTLEventError *e = dynamic_cast<
328  StApi::IStCallbackParamGenTLEventError*>(p);
329  msg.event_name = "Error";
330  msg.event_data = std::to_string(e->GetGCError()) + " " +
331  e->GetDescription().c_str();
332  }
333  publishEventDefault(msg);
334  }
335 
336  void StCameraInterface::eventInterfaceCB(StApi::IStCallbackParamBase *p,
337  void *pvContext)
338  {
339  if (destroyed_) return;
340  omronsentech_camera::Event msg;
341  msg.timestamp = ros::Time::now();
342  msg.module_name = "Interface";
343  if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_InterfaceError)
344  {
345  StApi::IStCallbackParamGenTLEventError *e = dynamic_cast<
346  StApi::IStCallbackParamGenTLEventError*>(p);
347  msg.event_name = "Error";
348  msg.event_data = std::to_string(e->GetGCError()) + " " +
349  e->GetDescription().c_str();
350  }
351  publishEventDefault(msg);
352  }
353 
354  void StCameraInterface::eventDeviceCB(StApi::IStCallbackParamBase *p,
355  void *pvContext)
356  {
357  if (destroyed_) return;
358  if (tl_dev_ && tl_dev_->IsDeviceLost()) return;
359  omronsentech_camera::Event msg;
360  msg.timestamp = ros::Time::now();
361  msg.module_name = "LocalDevice";
362  if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_DeviceError)
363  {
364  StApi::IStCallbackParamGenTLEventError *e = dynamic_cast<
365  StApi::IStCallbackParamGenTLEventError*>(p);
366  msg.event_name = "Error";
367  msg.event_data = std::to_string(e->GetGCError()) + " " +
368  e->GetDescription().c_str();
369  }
370  publishEventDefault(msg);
371  }
372 
373  void StCameraInterface::eventGenApiNodeCB(GenApi::INode *p, void *pvContext)
374  {
375  if (destroyed_) return;
376  MapCallback *cblist[5] =
377  {
383  };
384  std::string cbModule[5] =
385  {
386  "System", "Interface", "LocalDevice", "RemoteDevice", "DataStream"
387  };
388  MapCallback *cb = nullptr;
389  int index = -1;
390  std::string callback_node = p->GetName().c_str();
391 
392  // find the correct module
393  for (int i = 0; i < 5; i ++)
394  {
395  if (pvContext == (void*)(&(*cblist[i])))
396  {
397  cb = cblist[i];
398  index = i;
399  break;
400  }
401  }
402  if (-1 == index) return; // not found (shall never happen)
403 
404  omronsentech_camera::Event msg;
405  msg.timestamp = ros::Time::now();
406  msg.module_name = cbModule[index];
407  msg.callback_node = callback_node;
408  if (GenApi::IsReadable(p))
409  {
410  GenApi::CValuePtr pValue(p);
411  msg.event_data = pValue->ToString();
412  }
413  MapPublisher::iterator it = map_msg_event_.find(
414  ((*cb)[callback_node]).topic_name_);
415  if (it != map_msg_event_.end()) // publish to custom topic
416  {
417  it->second.publish(msg);
418  return;
419  }
420  publishEventDefault(msg); // publish to default topic
421  }
422 
423  void StCameraInterface::eventDataStreamCB(StApi::IStCallbackParamBase *p,
424  void *pvContext)
425  {
426  if (destroyed_) return;
427  if (p->GetCallbackType() ==
428  StApi::StCallbackType_GenTLEvent_DataStreamError)
429  {
430  omronsentech_camera::Event msg;
431  msg.timestamp = ros::Time::now();
432  msg.module_name = "DataStream";
433  StApi::IStCallbackParamGenTLEventError *e = dynamic_cast<
434  StApi::IStCallbackParamGenTLEventError*>(p);
435  msg.event_name = "Error";
436  msg.event_data = std::to_string(e->GetGCError()) + " " +
437  e->GetDescription().c_str();
438  publishEventDefault(msg);
439  return;
440  }
441 
442  if(p->GetCallbackType() ==
443  StApi::StCallbackType_GenTLEvent_DataStreamNewBuffer)
444  {
445  try
446  {
447  StApi::CIStStreamBufferPtr p_streambuffer(tl_ds_->RetrieveBuffer(0));
448 
449  if (it_campub_.getNumSubscribers() == 0 &&
451  {
452  return;
453  }
454 
455  omronsentech_camera::Chunk chunkdata;
456  bool has_chunk = false;
457  if (map_chunk_.size() > 0)
458  {
459  has_chunk = true;
460  GenApi::CNodeMapPtr cmp(p_streambuffer->GetChunkINodeMap());
461  for (MapChunk::iterator it = map_chunk_.begin();
462  it != map_chunk_.end(); it++)
463  {
464  GenApi::INode *node = it->second;
465  if (node == nullptr) continue;
466  switch(node->GetPrincipalInterfaceType())
467  {
468  case GenApi::intfIInteger:
469  {
470  GenApi::CIntegerPtr ptr(node);
471  omronsentech_camera::ElementInt64 data;
472  data.data = ptr->GetValue();
473  data.name = it->first;
474  chunkdata.int64_list.push_back(data);
475  break;
476  }
477  case GenApi::intfIFloat:
478  {
479  GenApi::CFloatPtr ptr(node);
480  omronsentech_camera::ElementFloat64 data;
481  data.data = ptr->GetValue();
482  data.name = it->first;
483  chunkdata.float64_list.push_back(data);
484  break;
485  }
486  case GenApi::intfIBoolean:
487  {
488  GenApi::CBooleanPtr ptr(node);
489  omronsentech_camera::ElementBool data;
490  data.data = ptr->GetValue();
491  data.name = it->first;
492  chunkdata.bool_list.push_back(data);
493  break;
494  }
495  case GenApi::intfIString:
496  {
497  GenApi::CStringPtr ptr(node);
498  omronsentech_camera::ElementString data;
499  data.data = ptr->GetValue();
500  data.name = it->first;
501  chunkdata.string_list.push_back(data);
502  break;
503  }
504  case GenApi::intfIValue:
505  {
506  GenApi::CValuePtr ptr(node);
507  omronsentech_camera::ElementString data;
508  data.data = ptr->ToString();
509  data.name = it->first;
510  chunkdata.string_list.push_back(data);
511  break;
512  }
513  }
514  }
515  }
516 
517  if (p_streambuffer->GetIStStreamBufferInfo()->IsImagePresent())
518  {
519  StApi::IStImage *p_stimage = p_streambuffer->GetIStImage();
520  const StApi::EStPixelFormatNamingConvention_t ePFNC =
521  p_stimage->GetImagePixelFormat();
522 
523  std::string encoding = "";
524  switch(ePFNC)
525  {
526  case StApi::StPFNC_BayerBG8:
528  break;
529  case StApi::StPFNC_BayerBG16:
531  break;
532  case StApi::StPFNC_BayerGB8:
534  break;
535  case StApi::StPFNC_BayerGB16:
537  break;
538  case StApi::StPFNC_BayerRG8:
540  break;
541  case StApi::StPFNC_BayerRG16:
543  break;
544  case StApi::StPFNC_BayerGR8:
546  break;
547  case StApi::StPFNC_BayerGR16:
549  break;
550  case StApi::StPFNC_Mono8:
552  break;
553  case StApi::StPFNC_Mono16:
555  break;
556  case StApi::StPFNC_RGB8:
558  break;
559  }
560  if (encoding.empty())
561  {
562  ROS_WARN("%s %s %d: %s: %ld: %ld x %ld: unknown encoding %d",
563  __FILE__,__func__,__LINE__,
564  camera_namespace_.c_str(),
565  p_streambuffer->GetIStStreamBufferInfo()->GetFrameID(),
566  p_stimage->GetImageWidth(),
567  p_stimage->GetImageHeight(),
568  (int)ePFNC);
569  return;
570  }
571 
572  StApi::IStPixelFormatInfo *const p_pixelformat_info =
573  StApi::GetIStPixelFormatInfo(ePFNC);
574  if (p_pixelformat_info->IsMono() || p_pixelformat_info->IsBayer() || p_pixelformat_info->IsColor())
575  {
576  //image data
577  sensor_msgs::ImagePtr image(new sensor_msgs::Image);
578  image->header.stamp = ros::Time((double)p_streambuffer
579  ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
580  image->header.frame_id = camera_namespace_;
581  image->width = p_stimage->GetImageWidth();
582  image->height = p_stimage->GetImageHeight();
583  image->step = p_stimage->GetImageLinePitch();
584  image->encoding = encoding;
585  image->is_bigendian = (p_streambuffer->GetIStStreamBufferInfo()
586  ->GetPixelEndianness() == GenTL::PIXELENDIANNESS_BIG);
587  const size_t buffer_size = image->height * image->step;
588  image->data.resize(buffer_size);
589  memcpy(&image->data[0], p_stimage->GetImageBuffer(), buffer_size);
590 
591  //camera info data
592  sensor_msgs::CameraInfoPtr ci(new sensor_msgs::CameraInfo(
593  cinfo_.getCameraInfo()));
594  ci->header.stamp = image->header.stamp;
595  if (it_campub_.getNumSubscribers() > 0)
596  {
597  it_campub_.publish(image, ci);
598  }
599 
600  if (has_chunk && msg_chunk_.getNumSubscribers() > 0)
601  {
602  chunkdata.timestamp = image->header.stamp;
603  msg_chunk_.publish(chunkdata);
604  }
605  }
606  }
607  else
608  {
609  if (has_chunk && msg_chunk_.getNumSubscribers() > 0)
610  {
611  chunkdata.timestamp = ros::Time((double)p_streambuffer
612  ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
613  msg_chunk_.publish(chunkdata);
614  }
615  }
616  }
617  catch(const StApi::CStGenTLErrorException &x)
618  {
619  ROS_ERROR("%s %s %d: \n\t%s GenTL error when retrieving payload: %d %s",
620  __FILE__,__func__,__LINE__,
621  camera_namespace_.c_str(), x.GetError(), x.GetDescription());
622  }
623  catch(GenICam::GenericException &x)
624  {
625  ROS_ERROR("%s %s %d: \n\t%s GenICam error when retrieving payload: %s",
626  __FILE__,__func__,__LINE__,
627  camera_namespace_.c_str(), x.GetDescription());
628  }
629  }
630  }
631 
632  // read node
634  omronsentech_camera::ReadNode::Request &req,
635  omronsentech_camera::ReadNode::Response &res)
636  {
637  try
638  {
639  GenApi::INodeMap* mp = getNodeMap(req.module_name);
641 
642  GenApi::INode *node = mp->GetNode(
643  GenICam::gcstring(req.node_name.c_str()));
645 
646  res.interface_type = GenApi::GetInterfaceName(node).c_str();
647  switch(node->GetPrincipalInterfaceType())
648  {
649  case GenApi::intfIInteger:
650  {
651  GenApi::CIntegerPtr ptr(node);
652  res.value = ptr->ToString();
653  return true;
654  }
655  case GenApi::intfIBoolean:
656  {
657  GenApi::CBooleanPtr ptr(node);
658  res.value = ptr->ToString();
659  return true;
660  }
661  case GenApi::intfIFloat:
662  {
663  GenApi::CFloatPtr ptr(node);
664  res.value = ptr->ToString();
665  return true;
666  }
667  case GenApi::intfIString:
668  {
669  GenApi::CStringPtr ptr(node);
670  res.value = ptr->GetValue().c_str();
671  return true;
672  }
673  case GenApi::intfIRegister:
674  {
675  GenApi::CRegisterPtr ptr(node);
676  res.value = ptr->ToString();
677  return true;
678  }
679  case GenApi::intfICategory:
680  {
681  GenApi::CCategoryPtr ptr(node);
682  res.value = ptr->ToString();
683  return true;
684  }
685  case GenApi::intfIEnumeration:
686  {
687  GenApi::CEnumerationPtr ptr(node);
688  res.value = ptr->ToString();
689  return true;
690  }
691  default:
692  {
694  }
695  }
696  }
698  }
699 
701  omronsentech_camera::ReadNodeBool::Request &req,
702  omronsentech_camera::ReadNodeBool::Response &res)
703  {
704  try
705  {
706  GenApi::INodeMap *mp = getNodeMap(req.module_name);
708 
709  GenApi::INode *node = mp->GetNode(
710  GenICam::gcstring(req.node_name.c_str()));
712 
713  GenApi::CBooleanPtr ptr(node);
714  res.value = ptr->GetValue();
715  return true;
716  }
718  }
719 
721  omronsentech_camera::ReadNodeEnum::Request &req,
722  omronsentech_camera::ReadNodeEnum::Response &res)
723  {
724  try
725  {
726  GenApi::INodeMap *mp = getNodeMap(req.module_name);
728 
729  GenApi::INode *node = mp->GetNode(
730  GenICam::gcstring(req.node_name.c_str()));
732 
733  GenApi::CEnumerationPtr ptr(node);
734  res.value_int = ptr->GetIntValue();
735  res.value_str = ptr->GetEntry(res.value_int)->GetSymbolic();
736  return true;
737  }
739  }
740 
742  omronsentech_camera::ReadNodeInt::Request &req,
743  omronsentech_camera::ReadNodeInt::Response &res)
744  {
745  try
746  {
747  GenApi::INodeMap *mp = getNodeMap(req.module_name);
749 
750  GenApi::INode *node = mp->GetNode(
751  GenICam::gcstring(req.node_name.c_str()));
753 
754  GenApi::CIntegerPtr ptr(node);
755  res.value = ptr->GetValue();
756  return true;
757  }
759  }
760 
762  omronsentech_camera::ReadNodeFloat::Request &req,
763  omronsentech_camera::ReadNodeFloat::Response &res)
764  {
765  try
766  {
767  GenApi::INodeMap *mp = getNodeMap(req.module_name);
769 
770  GenApi::INode *node = mp->GetNode(
771  GenICam::gcstring(req.node_name.c_str()));
773 
774  GenApi::CFloatPtr ptr(node);
775  res.value = ptr->GetValue();
776  return true;
777  }
779  }
780 
782  omronsentech_camera::ReadNodeString::Request &req,
783  omronsentech_camera::ReadNodeString::Response &res)
784  {
785  try
786  {
787  GenApi::INodeMap *mp = getNodeMap(req.module_name);
789 
790  GenApi::INode *node = mp->GetNode(
791  GenICam::gcstring(req.node_name.c_str()));
793 
794  GenApi::CStringPtr ptr(node);
795  res.value = ptr->GetValue();
796  return true;
797  }
799  }
800 
801  // write node
803  omronsentech_camera::WriteNode::Request &req,
804  omronsentech_camera::WriteNode::Response &res)
805  {
806  try
807  {
808  GenApi::INodeMap *mp = getNodeMap(req.module_name);
810 
811  GenApi::INode *node = mp->GetNode(
812  GenICam::gcstring(req.node_name.c_str()));
814 
815  switch(node->GetPrincipalInterfaceType())
816  {
817  case GenApi::intfIInteger:
818  {
819  GenApi::CIntegerPtr ptr(node);
820  ptr->SetValue(std::stoi(req.value));
821  return true;
822  }
823  case GenApi::intfIBoolean:
824  {
825  GenApi::CBooleanPtr ptr(node);
826  std::string true_str = "true";
827  std::string false_str = "false";
828  bool true_value = false;
829  bool false_value = false;
830  if (req.value.size() == true_str.size())
831  {
832  true_value = true;
833  for (std::string::const_iterator c1 = true_str.begin(),
834  c2 = req.value.begin(); c1 != true_str.end(); ++c1, ++c2)
835  {
836  if (tolower(*c1) != tolower(*c2))
837  {
838  true_value = false;
839  break;
840  }
841  }
842  if (true_value)
843  {
844  ptr->SetValue(true);
845  return true;
846  }
847  }
848  if (req.value.size() == false_str.size())
849  {
850  false_value = true;
851  for (std::string::const_iterator c1 = false_str.begin(),
852  c2 = req.value.begin(); c1 != false_str.end(); ++c1, ++c2)
853  {
854  if (tolower(*c1) != tolower(*c2))
855  {
856  false_value = false;
857  break;
858  }
859  }
860  if (false_value)
861  {
862  ptr->SetValue(false);
863  return true;
864  }
865  }
867  }
868  case GenApi::intfIFloat:
869  {
870  GenApi::CFloatPtr ptr(node);
871  ptr->SetValue(std::stod(req.value));
872  return true;
873  }
874  case GenApi::intfIString:
875  {
876  GenApi::CStringPtr ptr(node);
877  ptr->SetValue(GenICam::gcstring(req.value.c_str()));
878  return true;
879  }
880  case GenApi::intfIEnumeration:
881  {
882  GenApi::CEnumerationPtr ptr(node);
883  GenApi::CEnumEntryPtr enum_entry(
884  ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
885  ptr->SetIntValue(enum_entry->GetValue());
886  return true;
887  }
888  default:
889  {
891  }
892  }
893  }
895  }
896 
898  omronsentech_camera::WriteNodeBool::Request &req,
899  omronsentech_camera::WriteNodeBool::Response &res)
900  {
901  try
902  {
903  GenApi::INodeMap *mp = getNodeMap(req.module_name);
905 
906  GenApi::INode *node = mp->GetNode(
907  GenICam::gcstring(req.node_name.c_str()));
909 
910  GenApi::CBooleanPtr ptr(node);
911  ptr->SetValue(req.value);
912  return true;
913  }
915  }
916 
918  omronsentech_camera::WriteNodeEnumInt::Request &req,
919  omronsentech_camera::WriteNodeEnumInt::Response &res)
920  {
921  try
922  {
923  GenApi::INodeMap *mp = getNodeMap(req.module_name);
925 
926  GenApi::INode *node = mp->GetNode(
927  GenICam::gcstring(req.node_name.c_str()));
929 
930  GenApi::CEnumerationPtr ptr(node);
931  ptr->SetIntValue(req.value);
932  return true;
933  }
935  }
936 
938  omronsentech_camera::WriteNodeEnumStr::Request &req,
939  omronsentech_camera::WriteNodeEnumStr::Response &res)
940  {
941  try
942  {
943  GenApi::INodeMap *mp = getNodeMap(req.module_name);
945 
946  GenApi::INode *node = mp->GetNode(
947  GenICam::gcstring(req.node_name.c_str()));
949 
950  GenApi::CEnumerationPtr ptr(node);
951  GenApi::CEnumEntryPtr enum_entry(
952  ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
953  ptr->SetIntValue(enum_entry->GetValue());
954  return true;
955  }
957  }
958 
960  omronsentech_camera::WriteNodeInt::Request &req,
961  omronsentech_camera::WriteNodeInt::Response &res)
962  {
963  try
964  {
965  GenApi::INodeMap *mp = getNodeMap(req.module_name);
967 
968  GenApi::INode *node = mp->GetNode(
969  GenICam::gcstring(req.node_name.c_str()));
971 
972  GenApi::CIntegerPtr ptr(node);
973  ptr->SetValue(req.value);
974  return true;
975  }
977  }
978 
980  omronsentech_camera::WriteNodeFloat::Request &req,
981  omronsentech_camera::WriteNodeFloat::Response &res)
982  {
983  try
984  {
985  GenApi::INodeMap *mp = getNodeMap(req.module_name);
987 
988  GenApi::INode *node = mp->GetNode(
989  GenICam::gcstring(req.node_name.c_str()));
991 
992  GenApi::CFloatPtr ptr(node);
993  ptr->SetValue(req.value);
994 
995  return true;
996  }
998  }
999 
1001  omronsentech_camera::WriteNodeString::Request &req,
1002  omronsentech_camera::WriteNodeString::Response &res)
1003  {
1004  try
1005  {
1006  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1008 
1009  GenApi::INode *node = mp->GetNode(
1010  GenICam::gcstring(req.node_name.c_str()));
1012 
1013  GenApi::CStringPtr ptr(node);
1014 
1015  const GenICam::gcstring str = req.value.c_str();
1016  ptr->SetValue(str);
1017 
1018  return true;
1019  }
1020  CATCH_COMMON_ERR();
1021  }
1022 
1024  omronsentech_camera::ExecuteNode::Request &req,
1025  omronsentech_camera::ExecuteNode::Response &res)
1026  {
1027  try
1028  {
1029  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1031 
1032  GenApi::INode *node = mp->GetNode(
1033  GenICam::gcstring(req.node_name.c_str()));
1035 
1036  GenApi::CCommandPtr ptr(node);
1037  ptr->Execute();
1038  return true;
1039  }
1040  CATCH_COMMON_ERR();
1041  }
1042 
1043  // enable
1045  omronsentech_camera::EnableChunk::Request &req,
1046  omronsentech_camera::EnableChunk::Response &res)
1047  {
1048  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
1050  {
1052  }
1053 
1054  std::lock_guard<std::mutex> lock2(mtx_chunk_);
1055 
1056  try
1057  {
1058  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1059 
1060  GenApi::CEnumerationPtr chunk_selector(mp->GetNode(
1061  GenICam::gcstring("ChunkSelector")));
1062  GenApi::CBooleanPtr chunk_enable(mp->GetNode(
1063  GenICam::gcstring("ChunkEnable")));
1064  GenApi::CBooleanPtr chunk_active(mp->GetNode(
1065  GenICam::gcstring("ChunkModeActive")));
1066  if (!chunk_selector.IsValid() || !chunk_enable.IsValid() ||
1067  !chunk_active.IsValid())
1068  {
1070  }
1071 
1072  bool revert_chunk_mode = (false == chunk_active->GetValue());
1073  if (revert_chunk_mode)
1074  {
1075  chunk_active->SetValue(true);
1076  }
1077 
1078  if (req.chunk_name.empty()) // All chunks
1079  {
1080  GenApi::NodeList_t chunk_list;
1081  chunk_selector->GetEntries(chunk_list);
1082  for (GenApi::NodeList_t::iterator itr = chunk_list.begin();
1083  itr != chunk_list.end(); ++itr)
1084  {
1085  GenApi::CEnumEntryPtr chunk_list_entry(*itr);
1086  if (GenApi::IsAvailable(chunk_list_entry))
1087  {
1088  chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1089  if (GenApi::IsWritable(chunk_enable))
1090  {
1091  chunk_enable->SetValue(req.value);
1092  GenApi::CNodePtr chunk_value_node(mp->GetNode(
1093  "Chunk" + chunk_list_entry->GetSymbolic()));
1094  if (chunk_value_node && req.value)
1095  {
1096  MapChunk::iterator itm = map_chunk_.find(chunk_value_node
1097  ->GetName().c_str());
1098  if (itm == map_chunk_.end() || itm->second == nullptr)
1099  {
1100  map_chunk_[chunk_value_node->GetName().c_str()] =
1101  chunk_value_node;
1102  }
1103  }
1104  }
1105  }
1106  }
1107  if (!req.value)
1108  {
1109  map_chunk_.clear();
1110  chunk_active->SetValue(false);
1111  }
1112  }
1113  else
1114  {
1115  bool is_writable = true;
1116  bool all_chunk_disabled;
1117  GenApi::NodeList_t nodelist;
1118  GenApi::CEnumEntryPtr chunk_list_entry(chunk_selector
1119  ->GetEntryByName(GenICam::gcstring(req.chunk_name.c_str())));
1120  if (chunk_list_entry.IsValid() &&
1121  GenApi::IsReadable(chunk_list_entry))
1122  {
1123  chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1124  if (!GenApi::IsWritable(chunk_enable))
1125  {
1126  is_writable = false;
1127  }
1128  }
1129 
1130  if (!is_writable)
1131  {
1132  if (revert_chunk_mode)
1133  {
1134  chunk_active->SetValue(false);
1135  }
1137  }
1138 
1139  chunk_enable->SetValue(req.value);
1140 
1141  GenICam::gcstring chunk_value_name("Chunk");
1142  chunk_value_name.append(req.chunk_name.c_str());
1143  GenApi::CNodePtr chunk_value_node(mp->GetNode(chunk_value_name));
1144  if (chunk_value_node)
1145  {
1146  MapChunk::iterator itm = map_chunk_.find(chunk_value_node
1147  ->GetName().c_str());
1148  if (req.value)
1149  {
1150  if (itm == map_chunk_.end() || itm->second == nullptr)
1151  {
1152  map_chunk_[chunk_value_node->GetName().c_str()] =
1153  chunk_value_node;
1154  }
1155  }
1156  }
1157 
1158  // Disable chunk active if only Image is enabled.
1159  all_chunk_disabled = true;
1160  chunk_selector->GetEntries(nodelist);
1161  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1162  it != nodelist.end(); it++)
1163  {
1164  if (GenApi::IsAvailable(*it))
1165  {
1166  GenApi::CEnumEntryPtr enum_entry(*it);
1167  if (enum_entry->GetValue() == 0) continue; // skip image.
1168  chunk_selector->SetIntValue(enum_entry->GetValue());
1169  if (chunk_enable->GetValue() == true)
1170  {
1171  all_chunk_disabled = false;
1172  break;
1173  }
1174  }
1175  }
1176  if (all_chunk_disabled)
1177  {
1178  chunk_active->SetValue(false);
1179  }
1180  }
1181 
1182  return true;
1183  }
1184  CATCH_COMMON_ERR();
1185  }
1186 
1188  omronsentech_camera::EnableTrigger::Request &req,
1189  omronsentech_camera::EnableTrigger::Response &res)
1190  {
1191  try
1192  {
1193  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1194 
1195  // Node for selector and source
1196  GenApi::CEnumerationPtr trigger_selector(mp->GetNode(
1197  GenICam::gcstring("TriggerSelector")));
1198  GenApi::CEnumerationPtr trigger_source(mp->GetNode(
1199  GenICam::gcstring("TriggerSource")));
1200  if (!trigger_selector.IsValid() || !trigger_source.IsValid())
1201  {
1203  }
1204  GenApi::CEnumEntryPtr trigger_selector_entry(
1205  trigger_selector->GetEntryByName(
1206  GenICam::gcstring(req.trigger_selector.c_str())));
1207  GenApi::CEnumEntryPtr trigger_source_entry(
1208  trigger_source->GetEntryByName(
1209  GenICam::gcstring(req.trigger_source.c_str())));
1210  if (!trigger_selector_entry.IsValid() || !trigger_source_entry.IsValid())
1211  {
1213  }
1214 
1215  // set selector
1216  if (trigger_selector->GetIntValue() != trigger_selector_entry->GetValue())
1217  {
1218  trigger_selector->SetIntValue(trigger_selector_entry->GetValue());
1219  }
1220 
1221  // set source
1222  if (trigger_source->GetIntValue() != trigger_source_entry->GetValue())
1223  {
1224  trigger_source->SetIntValue(trigger_source_entry->GetValue());
1225  }
1226 
1227  // set delay only if supported
1228  GenApi::CFloatPtr trigger_delay = mp->GetNode(
1229  GenICam::gcstring("TriggerDelay"));
1230  if (trigger_delay.IsValid())
1231  {
1232  if (trigger_delay->GetValue() != req.trigger_delayus)
1233  {
1234  trigger_delay->SetValue(req.trigger_delayus);
1235  }
1236  }
1237 
1238  // set mode
1239  GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1240  GenICam::gcstring("TriggerMode"));
1241  if (req.value == true)
1242  {
1243  GenApi::CEnumEntryPtr trigger_mode_entry(
1244  trigger_mode->GetEntryByName(GenICam::gcstring("On")));
1245  if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1246  {
1247  trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1248  }
1249  }
1250  else
1251  {
1252  GenApi::CEnumEntryPtr trigger_mode_entry(
1253  trigger_mode->GetEntryByName(GenICam::gcstring("Off")));
1254  if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1255  {
1256  trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1257  }
1258  }
1259  return true;
1260  }
1261  CATCH_COMMON_ERR();
1262  }
1263 
1265  omronsentech_camera::EnableEventNode::Request &req,
1266  omronsentech_camera::EnableEventNode::Response &res)
1267  {
1268  std::lock_guard<std::mutex> lock(mtx_event_);
1269  try
1270  {
1271  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1273 
1274  GenApi::INode *nodeCallback = mp->GetNode(
1275  GenICam::gcstring(req.callback_node.c_str()));
1276  CHECK_NULLPTR(nodeCallback, NODE_ERROR, NODE_ERROR_STR);
1277 
1278  GenApi::CEnumerationPtr event_selector(mp->GetNode(
1279  GenICam::gcstring("EventSelector")));
1280  GenApi::CEnumerationPtr event_notif(mp->GetNode(
1281  GenICam::gcstring("EventNotification")));
1282  if (!event_selector.IsValid() || !event_notif.IsValid() ||
1283  !GenApi::IsWritable(event_selector))
1284  {
1286  }
1287 
1288  GenApi::CEnumEntryPtr enum_entry(
1289  event_selector->GetEntryByName(
1290  GenICam::gcstring(req.node_name.c_str())));
1291  if (!enum_entry.IsValid())
1292  {
1294  }
1295  event_selector->SetIntValue(enum_entry->GetValue());
1296  GenApi::CNodePtr node_callback(nodeCallback);
1297  GenICam::gcstring value = req.value ? "On" : "Off";
1298  GenApi::CEnumEntryPtr event_notif_entry(
1299  event_notif->GetEntryByName(value));
1300  if (!GenApi::IsWritable(event_notif))
1301  {
1303  }
1304  event_notif->SetIntValue(event_notif_entry->GetValue());
1305 
1306  MapCallback *cb = getCallbackMap(req.module_name);
1307  MapCallback::iterator it = cb->find(req.callback_node);
1308  std::string topic_name = STMSG_event;
1309  if (!req.event_topic_name.empty())
1310  {
1311  topic_name += "/" + req.event_topic_name;
1312  }
1313 
1314  if (req.value) // set enabled = true
1315  {
1316  if (it == cb->end()) // not found in registered list
1317  {
1318  MapPublisher::iterator itpub = map_msg_event_.find(topic_name);
1319  if (itpub == map_msg_event_.end())
1320  {
1321  map_msg_event_.insert(std::pair<std::string, ros::Publisher>(
1322  topic_name,
1323  nh_.advertise<omronsentech_camera::Event>(topic_name,
1324  queue_size_)));
1325  }
1326  struct StCallback stc;
1327  stc.topic_name_ = topic_name;
1328  stc.cb_ = StApi::RegisterCallback(node_callback, *this,
1330  (void*)(&(*cb)), GenApi::cbPostInsideLock);
1331  (*cb)[req.callback_node] = stc;
1332  return true;
1333  }
1334  // already registered
1336  }
1337 
1338  // set enabled = false
1339  if (it != cb->end()) // found in registered list
1340  {
1341  StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
1342  cbf->Release();
1343  cb->erase(it);
1344  if (topic_name.compare(std::string(camera_namespace_ +
1345  "/" + STMSG_event)) != 0) // not using default event topic
1346  {
1347  // remove publisher if no other event callback is using the topic
1348  MapCallback *cblist[5] =
1349  {
1355  };
1356  for (int i = 0; i < 5; i++)
1357  {
1358  for (MapCallback::iterator itcb = (*cblist[i]).begin();
1359  itcb != (*cblist[i]).end(); itcb++)
1360  { // if other event is using the topic, do nothing and return.
1361  if (itcb->second.topic_name_.compare(topic_name) == 0)
1362  {
1363  return true;
1364  }
1365  }
1366  }
1367  MapPublisher::iterator itpub = map_msg_event_.find(topic_name);
1368  if (itpub != map_msg_event_.end())
1369  {
1370  map_msg_event_.erase(itpub);
1371  }
1372  }
1373  return true;
1374  }
1375  // not found in registered list
1377  }
1378  CATCH_COMMON_ERR();
1379  }
1380 
1382  omronsentech_camera::EnableImageAcquisition::Request &req,
1383  omronsentech_camera::EnableImageAcquisition::Response &res)
1384  {
1385  std::lock_guard<std::mutex> lock(mtx_acquisition_);
1386  try
1387  {
1388  if (req.value == true)
1389  {
1390  //already started, return directly
1392  {
1394  }
1395 
1397  tl_ds_->StartAcquisition();
1398  tl_dev_->AcquisitionStart();
1400  return true;
1401  }
1402 
1404  {
1405  tl_dev_->AcquisitionStop();
1406  tl_ds_->StopAcquisition();
1408  return true;
1409  }
1411  }
1412  CATCH_COMMON_ERR();
1413  }
1414 
1416  omronsentech_camera::EnableEventAcquisition::Request &req,
1417  omronsentech_camera::EnableEventAcquisition::Response &res)
1418  {
1419  std::lock_guard<std::mutex> lock(mtx_event_);
1420  try
1421  {
1422  StApi::IStEventCtrl *event_control = nullptr;
1423  bool *event_value = nullptr;
1424  if (req.module_name.compare("System") == 0)
1425  {
1426  event_control = dynamic_cast<StApi::IStEventCtrl *>(
1427  tl_dev_->GetIStInterface()->GetIStSystem());
1428  event_value = &bool_event_system_;
1429  }
1430  else if (req.module_name.compare("Interface") == 0)
1431  {
1432  event_control = dynamic_cast<StApi::IStEventCtrl *>(
1433  tl_dev_->GetIStInterface());
1434  event_value = &bool_event_interface_;
1435  }
1436  else if (req.module_name.compare("LocalDevice") == 0)
1437  {
1438  event_control = dynamic_cast<StApi::IStEventCtrl *>(&(*tl_dev_));
1439  //(StApi::IStDevice*)tl_dev_);
1440  event_value = &bool_event_device_;
1441  }
1442  else if (req.module_name.compare("DataStream") == 0)
1443  {
1444  event_control = dynamic_cast<StApi::IStEventCtrl *>(&(*tl_ds_));
1445  event_value = &bool_event_datastream_;
1446  }
1447  else
1448  {
1450  }
1451 
1452  if (event_control != nullptr)
1453  {
1454  if (req.value == true) // set enable
1455  {
1456  if (req.value == *event_value)
1457  {
1459  }
1460  event_control->StartEventAcquisitionThread();
1461  *event_value = true;
1462  return true;
1463  }
1464 
1465  // set disable
1466  if (req.value == *event_value)
1467  {
1469  }
1470  event_control->StopEventAcquisitionThread();
1471  *event_value = false;
1472  return true;
1473  }
1474  }
1475  CATCH_COMMON_ERR();
1476  }
1477 
1478  // get
1480  omronsentech_camera::GetImageAcquisitionStatus::Request &req,
1481  omronsentech_camera::GetImageAcquisitionStatus::Response &res)
1482  {
1483  std::lock_guard<std::mutex> lock(mtx_acquisition_);
1484  res.value = bool_acquisition_is_started_;
1485  return true;
1486  }
1487 
1489  omronsentech_camera::GetEventAcquisitionStatusList::Request &req,
1490  omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
1491  {
1492  std::lock_guard<std::mutex> lock(mtx_event_);
1493  res.module_name_list.push_back("System");
1494  res.module_name_list.push_back("Interface");
1495  res.module_name_list.push_back("LocalDevice");
1496  res.module_name_list.push_back("RemoteDevice");
1497  res.module_name_list.push_back("DataStream");
1498  res.enabled_list.push_back(bool_event_system_);
1499  res.enabled_list.push_back(bool_event_interface_);
1500  res.enabled_list.push_back(bool_event_device_); //Local == Remote
1501  res.enabled_list.push_back(bool_event_device_); //Remote == Local
1502  res.enabled_list.push_back(bool_event_datastream_);
1503  return true;
1504  }
1505 
1507  omronsentech_camera::GetEventNodeStatusList::Request &req,
1508  omronsentech_camera::GetEventNodeStatusList::Response &res)
1509  {
1510  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1512 
1513  try
1514  {
1515  GenApi::CEnumerationPtr event_selector(mp->GetNode(
1516  GenICam::gcstring("EventSelector")));
1517  GenApi::CEnumerationPtr event_notif(mp->GetNode(
1518  GenICam::gcstring("EventNotification")));
1519  if (!event_selector.IsValid() || !event_notif.IsValid())
1520  {
1522  }
1523  if (GenApi::IsReadable(event_selector))
1524  {
1525  GenApi::NodeList_t nodelist;
1526  event_selector->GetEntries(nodelist);
1527  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1528  it != nodelist.end(); it++)
1529  {
1530  if (!GenApi::IsAvailable(*it)) continue;
1531 
1532  GenApi::CEnumEntryPtr enum_entry(*it);
1533  event_selector->SetIntValue(enum_entry->GetValue());
1534  omronsentech_camera::GenICamEvent genicam_event;
1535  genicam_event.name = std::string(enum_entry->GetSymbolic().c_str());
1536  genicam_event.enabled = (event_notif->GetCurrentEntry()
1537  ->GetSymbolic().compare("On") == 0 ? true : false);
1538 
1539  //list the callback node:
1540  std::string nodeData = "Event" + genicam_event.name + "Data";
1541  GenApi::CNodePtr event_category_node(mp->GetNode(
1542  GenICam::gcstring(nodeData.c_str())));
1543  if (event_category_node.IsValid())
1544  {
1545  MapCallback *cb = getCallbackMap(req.module_name);
1546  GenApi::FeatureList_t features;
1547  GenApi::CCategoryPtr event_category(event_category_node);
1548  event_category->GetFeatures(features);
1549  for (GenApi::FeatureList_t::iterator it = features.begin();
1550  it != features.end(); it++)
1551  {
1552  GenApi::INode *node = (*it)->GetNode();
1553  if (!GenApi::IsImplemented(node)) continue;
1554  std::string cb_name = node->GetName().c_str();
1555  genicam_event.callback_node_list.push_back(cb_name.c_str());
1556  MapCallback::iterator itmap = cb->find(cb_name);
1557  if (itmap == cb->end() || itmap->second.cb_ == nullptr)
1558  {
1559  genicam_event.callback_enabled_list.push_back(false);
1560  }
1561  else
1562  {
1563  genicam_event.callback_enabled_list.push_back(true);
1564  }
1565  }
1566  }
1567  res.event_node_list.push_back(genicam_event);
1568  }
1569  }
1570  return true;
1571  }
1572  CATCH_COMMON_ERR();
1573  }
1574 
1576  omronsentech_camera::GetChunkList::Request &req,
1577  omronsentech_camera::GetChunkList::Response &res)
1578  {
1579  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
1581  {
1583  }
1584 
1585  std::lock_guard<std::mutex> lock2(mtx_chunk_);
1586  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1587  try
1588  {
1589  GenApi::CEnumerationPtr chunk_selector = mp->GetNode(
1590  GenICam::gcstring("ChunkSelector"));
1591  GenApi::NodeList_t nodelist;
1592  if (!chunk_selector.IsValid())
1593  {
1595  }
1596 
1597  GenApi::CBooleanPtr chunk_active = mp->GetNode(
1598  GenICam::gcstring("ChunkModeActive"));
1599  bool revert_chunk_mode = (false == chunk_active->GetValue());
1600  if (revert_chunk_mode)
1601  {
1602  chunk_active->SetValue(true);
1603  }
1604  chunk_selector->GetEntries(nodelist);
1605  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1606  it != nodelist.end(); it++)
1607  {
1608  if (GenApi::IsAvailable(*it))
1609  {
1610  GenApi::CEnumEntryPtr enum_entry(*it);
1611  res.chunk_name_list.push_back(
1612  std::string(enum_entry->GetSymbolic().c_str()));
1613  chunk_selector->SetIntValue(enum_entry->GetValue());
1614  GenApi::CBooleanPtr enablePtr = mp->GetNode(
1615  GenICam::gcstring("ChunkEnable"));
1616  if (enablePtr.IsValid())
1617  {
1618  res.chunk_enabled_list.push_back(
1619  enablePtr->GetValue() ? true : false);
1620  }
1621  }
1622  }
1623  if (revert_chunk_mode)
1624  {
1625  chunk_active->SetValue(false);
1626  }
1627 
1628  return true;
1629  }
1630  CATCH_COMMON_ERR();
1631  }
1632 
1634  omronsentech_camera::GetTriggerList::Request &req,
1635  omronsentech_camera::GetTriggerList::Response &res)
1636  {
1637  try
1638  {
1639  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1640 
1641  // Node for selector and source
1642  GenApi::CEnumerationPtr enum_sel = mp->GetNode(
1643  GenICam::gcstring("TriggerSelector"));
1644  GenApi::CEnumerationPtr enum_src = mp->GetNode(
1645  GenICam::gcstring("TriggerSource"));
1646  if (!enum_sel.IsValid() || !enum_src.IsValid())
1647  {
1649  }
1650 
1651  // Iterate selector
1652  GenApi::NodeList_t nodelist;
1653  enum_sel->GetEntries(nodelist);
1654  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1655  it != nodelist.end(); it++)
1656  {
1657  if (!GenApi::IsAvailable(*it)) continue;
1658  // Get selector
1659  GenApi::CEnumEntryPtr enum_entry(*it);
1660  res.trigger_selector_list.push_back(
1661  std::string(enum_entry->GetSymbolic().c_str()));
1662  enum_sel->SetIntValue(enum_entry->GetValue());
1663 
1664  // Get mode
1665  GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1666  GenICam::gcstring("TriggerMode"));
1667  if (trigger_mode.IsValid())
1668  {
1669  res.trigger_mode_list.push_back(trigger_mode->GetCurrentEntry()
1670  ->GetSymbolic().compare("On") == 0 ? true : false);
1671  }
1672  else
1673  {
1674  res.trigger_mode_list.push_back(false);
1675  }
1676 
1677  // Get delayus
1678  GenApi::CFloatPtr trigger_delay = mp->GetNode(
1679  GenICam::gcstring("TriggerDelay"));
1680  if (trigger_mode.IsValid() && GenApi::IsReadable(trigger_delay))
1681  {
1682  res.trigger_delayus_list.push_back(trigger_delay->GetValue());
1683  }
1684  else
1685  {
1686  res.trigger_delayus_list.push_back(0);
1687  }
1688  }
1689 
1690  // Iterate source
1691  nodelist.clear();
1692  enum_src->GetEntries(nodelist);
1693  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1694  it != nodelist.end(); it++)
1695  {
1696  if (!GenApi::IsAvailable(*it)) continue;
1697  // Get source
1698  GenApi::CEnumEntryPtr enum_entry(*it);
1699  res.trigger_source_list.push_back(
1700  std::string(enum_entry->GetSymbolic().c_str()));
1701  }
1702  return true;
1703  }
1704  CATCH_COMMON_ERR();
1705  }
1706 
1708  omronsentech_camera::GetEnumList::Request &req,
1709  omronsentech_camera::GetEnumList::Response &res)
1710  {
1711  try
1712  {
1713  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1715 
1716  GenApi::INode *node = mp->GetNode(
1717  GenICam::gcstring(req.node_name.c_str()));
1719 
1720  GenApi::CEnumerationPtr ptr(node);
1721  GenApi::NodeList_t nodelist;
1722  ptr->GetEntries(nodelist);
1723  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1724  it != nodelist.end(); it++)
1725  {
1726  if (GenApi::IsAvailable(*it))
1727  {
1728  GenApi::CEnumEntryPtr enum_entry(*it);
1729  res.enum_value_int_list.push_back(enum_entry->GetValue());
1730  res.enum_value_str_list.push_back(
1731  std::string(enum_entry->GetSymbolic().c_str()));
1732  }
1733  }
1734  return true;
1735  }
1736  CATCH_COMMON_ERR();
1737  }
1738 
1740  omronsentech_camera::GetGenICamNodeInfo::Request &req,
1741  omronsentech_camera::GetGenICamNodeInfo::Response &res)
1742  {
1743  try
1744  {
1745  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1747 
1748  GenApi::INode *node = mp->GetNode(
1749  GenICam::gcstring(req.node_name.c_str()));
1751 
1752  //string name
1753  res.name = node->GetName().c_str();
1754 
1755  //string description
1756  res.description = node->GetDescription().c_str();
1757 
1758  //string name_space
1759  GenApi::ENameSpace genicam_namespace = node->GetNameSpace();
1760  switch(genicam_namespace)
1761  {
1762  case(GenApi::Custom):
1763  res.name_space = "Custom";
1764  break;
1765  case(GenApi::Standard):
1766  res.name_space= "Standard";
1767  break;
1768  case(GenApi::_UndefinedNameSpace):
1769  default:
1770  res.name_space = "";
1771  break;
1772  }
1773 
1774  //string interface_type
1775  res.interface_type = GenApi::GetInterfaceName(node).c_str();
1776 
1777  //string access_mode
1778  GenApi::EAccessMode genicam_accessmode = node->GetAccessMode();
1779  switch(genicam_accessmode)
1780  {
1781  case(GenApi::NI):
1782  res.access_mode = "Not implemented";
1783  break;
1784  case(GenApi::NA):
1785  res.access_mode = "Not available";
1786  break;
1787  case(GenApi::WO):
1788  res.access_mode = "Write Only";
1789  break;
1790  case(GenApi::RO):
1791  res.access_mode = "Read Only";
1792  break;
1793  case(GenApi::RW):
1794  res.access_mode = "Read and Write";
1795  break;
1796  case(GenApi::_CycleDetectAccesMode):
1797  res.access_mode = "used internally for AccessMode cycle detection";
1798  break;
1799  case(GenApi::_UndefinedAccesMode):
1800  default:
1801  res.access_mode = "";
1802  break;
1803  }
1804 
1805  //string is_cachable
1806  GenApi::EYesNo genicam_accessmode_cacheable =
1807  node->IsAccessModeCacheable();
1808  switch(genicam_accessmode_cacheable)
1809  {
1810  case(GenApi::Yes):
1811  res.is_cachable = "Yes";
1812  break;
1813  case(GenApi::No):
1814  res.is_cachable = "No";
1815  break;
1816  case(GenApi::_UndefinedYesNo):
1817  default:
1818  res.is_cachable = "";
1819  break;
1820  }
1821 
1822  //string visibility
1823  GenApi::EVisibility genicam_visibility = node->GetVisibility();
1824  switch(genicam_visibility)
1825  {
1826  case(GenApi::Beginner):
1827  res.visibility = "Beginner";
1828  break;
1829  case(GenApi::Expert):
1830  res.visibility = "Expert";
1831  break;
1832  case(GenApi::Guru):
1833  res.visibility = "Guru";
1834  break;
1835  case(GenApi::Invisible):
1836  res.visibility = "Invisible";
1837  break;
1838  case(GenApi::_UndefinedVisibility):
1839  default:
1840  res.visibility = "";
1841  }
1842 
1843  //string caching_mode
1844  GenApi::ECachingMode genicam_caching_mode = node->GetCachingMode();
1845  switch(genicam_caching_mode)
1846  {
1847  case(GenApi::NoCache):
1848  res.caching_mode = "Does not use cache";
1849  break;
1850  case(GenApi::WriteThrough):
1851  res.caching_mode = "Write to cache and register";
1852  break;
1853  case(GenApi::WriteAround):
1854  res.caching_mode = "Write to register, write to cache on read";
1855  break;
1856  case(GenApi::_UndefinedCachingMode):
1857  default:
1858  res.caching_mode = "";
1859  }
1860 
1861  //bool is_streamable
1862  res.is_streamable = node->IsStreamable() ? true : false;
1863 
1864  if (genicam_accessmode == GenApi::NA)
1865  {
1866  return true;
1867  }
1868 
1869  if (genicam_accessmode == GenApi::RW || genicam_accessmode == GenApi::RO)
1870  {
1871  switch(node->GetPrincipalInterfaceType())
1872  {
1873  case GenApi::intfIValue:
1874  {
1875  GenApi::CValuePtr ptr(node);
1876  res.current_value = ptr->ToString();
1877  break;
1878  }
1879  case GenApi::intfIInteger:
1880  {
1881  GenApi::CIntegerPtr ptr(node);
1882  res.current_value = ptr->ToString();
1883  res.min_value = std::to_string(ptr->GetMin());
1884  res.max_value = std::to_string(ptr->GetMax());
1885  res.unit = ptr->GetUnit().c_str();
1886  try
1887  {
1888  res.increment = std::to_string(ptr->GetInc());
1889  }
1890  catch(...)
1891  {
1892  res.increment = "";
1893  }
1894  break;
1895  }
1896  case GenApi::intfIBoolean:
1897  {
1898  GenApi::CBooleanPtr ptr(node);
1899  res.current_value = ptr->ToString();
1900  break;
1901  }
1902  case GenApi::intfICommand:
1903  {
1904  break;
1905  }
1906  case GenApi::intfIFloat:
1907  {
1908  GenApi::CFloatPtr ptr(node);
1909  res.current_value = ptr->ToString();
1910  res.min_value = std::to_string(ptr->GetMin());
1911  res.max_value = std::to_string(ptr->GetMax());
1912  res.unit = ptr->GetUnit().c_str();
1913  break;
1914  }
1915  case GenApi::intfIString:
1916  {
1917  GenApi::CStringPtr ptr(node);
1918  res.current_value = ptr->GetValue().c_str();
1919  break;
1920  }
1921  case GenApi::intfIRegister:
1922  {
1923  GenApi::CRegisterPtr ptr(node);
1924  res.current_value = ptr->ToString();
1925  break;
1926  }
1927  case GenApi::intfICategory:
1928  {
1929  GenApi::CCategoryPtr ptr(node);
1930  res.current_value = ptr->ToString();
1931  GenApi::FeatureList_t features;
1932  ptr->GetFeatures(features);
1933  for (GenApi::FeatureList_t::iterator it = features.begin();
1934  it != features.end(); it++)
1935  {
1936  GenApi::INode *node = (*it)->GetNode();
1937  if (!GenApi::IsImplemented(node)) continue;
1938  res.child_node_list.push_back(node->GetName().c_str());
1939  }
1940  break;
1941  }
1942  case GenApi::intfIEnumeration:
1943  {
1944  GenApi::CEnumerationPtr ptr(node);
1945  res.current_value = ptr->ToString();
1946  GenApi::NodeList_t nodelist;
1947  ptr->GetEntries(nodelist);
1948  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1949  it != nodelist.end(); it++)
1950  {
1951  if (GenApi::IsAvailable(*it))
1952  {
1953  GenApi::CEnumEntryPtr enum_entry(*it);
1954  res.enum_value_int_list.push_back(enum_entry->GetValue());
1955  res.enum_value_str_list.push_back(
1956  std::string(enum_entry->GetSymbolic().c_str()));
1957  }
1958  }
1959  break;
1960  }
1961  case GenApi::intfIEnumEntry:
1962  {
1963  GenApi::CEnumEntryPtr ptr(node);
1964  res.current_value = ptr->ToString();
1965  break;
1966  }
1967  case GenApi::intfIPort:
1968  {
1969  break;
1970  }
1971  default:
1972  {
1974  }
1975  }
1976  }
1977  return true;
1978  }
1979  CATCH_COMMON_ERR();
1980  }
1981 
1983  omronsentech_camera::SendSoftTrigger::Request &req,
1984  omronsentech_camera::SendSoftTrigger::Response &res)
1985  {
1986  try
1987  {
1988  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1989 
1990  //set selector
1991  GenApi::CEnumerationPtr enum_node = mp->GetNode(
1992  GenICam::gcstring("TriggerSelector"));
1993  GenApi::CEnumEntryPtr enum_entry(enum_node->GetEntryByName(
1994  GenICam::gcstring(req.trigger_selector.c_str())));
1995  if (enum_node->GetIntValue() != enum_entry->GetValue())
1996  {
1997  enum_node->SetIntValue(enum_entry->GetValue());
1998  }
1999 
2000  //send
2001  GenApi::CCommandPtr cmd = mp->GetNode(
2002  GenICam::gcstring("TriggerSoftware"));
2003  cmd->Execute();
2004  return true;
2005  }
2006  CATCH_COMMON_ERR();
2007  }
2008 
2010  omronsentech_camera::GetLastError::Request &req,
2011  omronsentech_camera::GetLastError::Response &res)
2012  {
2013  res.error_code = last_error_;
2014  switch(last_error_)
2015  {
2016  case 0:
2017  res.description = "No error.";
2018  return true;
2019  case UNKNOWN_ERROR:
2020  res.description = "Unknown exception occured.";
2021  return true;
2022  case GENICAM_ERROR:
2023  res.description = "Error occured when accessing GenICam code. If image acquisition is enabled, try to disable image acquisition before accessing the node.";
2024  return true;
2025  case MODULE_ERROR:
2026  res.description = "Module name is invalid. Check the list of "
2027  "module name by calling service 'get_module_list'";
2028  return true;
2029  case NODE_ERROR:
2030  res.description = "Either GenICam node name is invalid or "
2031  "the node is inaccessible.";
2032  return true;
2034  res.description = "Event already started.";
2035  return true;
2037  res.description = "Event already terminated.";
2038  return true;
2039  case ACQ_ALREADY_ON_ERROR:
2040  res.description = "Acquisition already started so that the requested "
2041  "operation cannot be processed.";
2042  return true;
2043  case ACQ_ALREADY_OFF_ERROR:
2044  res.description = "Acquisition already disabled so that the requested "
2045  "operation cannot be processed.";
2046  return true;
2048  res.description = "This device does not support chunk.";
2049  return true;
2050  case CHUNK_NAME_ERROR:
2051  res.description = "The given chunk name does not exist or not "
2052  "available.";
2053  return true;
2055  res.description = "Either trigger is not supported OR the GenICam node is non-standard. Please directly access the GenICam node.";
2056  return true;
2057  case TRIGGER_NAME_ERROR:
2058  res.description = "The given trigger selector and/or the source "
2059  "does not exist or not available.";
2060  return true;
2062  res.description = "Either Event callback is not supported or "
2063  "not available.";
2064  return true;
2065  case EVENT_NAME_ERROR:
2066  res.description = "The given event name and/or callback node "
2067  "does not exist or not available.";
2068  return true;
2069  }
2070 
2071  if ((last_error_ < -1000 && last_error_ > -1023) ||
2072  last_error_ <= -10000)
2073  {
2074  res.description = "GenTL error code. "
2075  "Please refer to GenTL documentation.";
2076  return true;
2077  }
2078  res.description = "Error code is unknown.";
2079  return true;
2080  }
2081 
2082 
2084  {
2085  // camera name
2087  {
2088  ROS_WARN("Unable to set camera name %s", camera_namespace_.c_str());
2089  }
2090 
2091  // calibration file
2092  std::string calibration_file = param_->getCalibrationFile(nh_,
2094  if (!calibration_file.empty())
2095  {
2096  ROS_INFO("Calib file %s: %s",camera_namespace_.c_str(),
2097  calibration_file.c_str());
2098  if (cinfo_.validateURL(calibration_file))
2099  {
2100  cinfo_.loadCameraInfo(calibration_file);
2101  }
2102  else
2103  {
2104  ROS_WARN("%s Invalid calibration file %s",
2105  camera_namespace_.c_str(), calibration_file.c_str());
2106  }
2107  }
2108  else
2109  {
2110  ROS_WARN("%s No calibration file found", camera_namespace_.c_str());
2111  }
2112 
2113  try
2114  {
2115  sensor_msgs::CameraInfoPtr cam_info(new sensor_msgs::CameraInfo(
2116  cinfo_.getCameraInfo()));
2117  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
2118 
2119  // frame id
2120  cam_info->header.frame_id = camera_namespace_;
2121 
2122  // binning x
2123  GenApi::CIntegerPtr bin_h_val(mp->GetNode(
2124  GenICam::gcstring("DecimationHorizontal")));
2125  cam_info->binning_x = bin_h_val->GetValue();
2126 
2127  // binning y
2128  GenApi::CIntegerPtr bin_v_val(mp->GetNode(
2129  GenICam::gcstring("DecimationVertical")));
2130  cam_info->binning_y = bin_v_val->GetValue();
2131 
2132  // width
2133  GenApi::CIntegerPtr width_max_val(mp->GetNode(
2134  GenICam::gcstring("WidthMax")));
2135  cam_info->width = width_max_val->GetValue();
2136 
2137  // height
2138  GenApi::CIntegerPtr height_max_val(mp->GetNode(
2139  GenICam::gcstring("HeightMax")));
2140  cam_info->height = height_max_val->GetValue();
2141 
2142  // ROI
2143  GenApi::CNodePtr roi_node(mp->GetNode(
2144  GenICam::gcstring("RegionSelector")));
2145  if (GenApi::IsWritable(roi_node))
2146  {
2147  GenApi::CEnumerationPtr roi_val(roi_node);
2148  GenApi::CEnumEntryPtr roi_entry(roi_val->GetEntryByName(
2149  GenICam::gcstring("Region0")));
2150  roi_val->SetIntValue(roi_entry->GetValue());
2151  GenApi::CIntegerPtr width(mp->GetNode(GenICam::gcstring("Width")));
2152  GenApi::CIntegerPtr height(mp->GetNode(GenICam::gcstring("Height")));
2153  GenApi::CIntegerPtr offsetx(mp->GetNode(GenICam::gcstring("OffsetX")));
2154  GenApi::CIntegerPtr offsety(mp->GetNode(GenICam::gcstring("OffsetY")));
2155  if (GenApi::IsReadable(width))
2156  {
2157  cam_info->roi.x_offset = offsetx->GetValue();
2158  cam_info->roi.y_offset = offsety->GetValue();
2159  if (width->GetValue() != cam_info->width ||
2160  height->GetValue() != cam_info->height)
2161  {
2162  cam_info->roi.width = width->GetValue();
2163  cam_info->roi.height = height->GetValue();
2164  }
2165  }
2166  cam_info->roi.do_rectify =
2167  (cam_info->roi.width > 0 && cam_info->roi.width < cam_info->width) ||
2168  (cam_info->roi.height > 0 && cam_info->roi.height < cam_info->height);
2169  }
2170  cinfo_.setCameraInfo(*cam_info);
2171  }
2172  catch(...)
2173  {
2174  }
2175  }
2176 
2177  GenApi::INodeMap *StCameraInterface::getNodeMap(std::string &module_name)
2178  {
2179  if (module_name.compare("System") == 0)
2180  {
2181  return tl_dev_->GetIStInterface()->GetIStSystem()->GetIStPort()
2182  ->GetINodeMap();
2183  }
2184  if (module_name.compare("Interface") == 0)
2185  {
2186  return tl_dev_->GetIStInterface()->GetIStPort()->GetINodeMap();
2187  }
2188  if (module_name.compare("LocalDevice") == 0)
2189  {
2190  return tl_dev_->GetLocalIStPort()->GetINodeMap();
2191  }
2192  if (module_name.compare("RemoteDevice") == 0)
2193  {
2194  return tl_dev_->GetRemoteIStPort()->GetINodeMap();
2195  }
2196  if (module_name.compare("DataStream") == 0)
2197  {
2198  return tl_ds_->GetIStPort()->GetINodeMap();
2199  }
2200  return nullptr;
2201  }
2202 
2204  {
2205  if (module_name.compare("System") == 0)
2206  {
2207  return &map_event_system_;
2208  }
2209  if (module_name.compare("Interface") == 0)
2210  {
2211  return &map_event_interface_;
2212  }
2213  if (module_name.compare("LocalDevice") == 0)
2214  {
2215  return &map_event_localdevice_;
2216  }
2217  if (module_name.compare("RemoteDevice") == 0)
2218  {
2219  return &map_event_remotedevice_;
2220  }
2221  if (module_name.compare("DataStream") == 0)
2222  {
2223  return &map_event_datastream_;
2224  }
2225  return nullptr;
2226  }
2227 
2228  void StCameraInterface::publishEventDefault(omronsentech_camera::Event &msg)
2229  {
2230  std::string default_event = STMSG_event;
2231  MapPublisher::iterator it = map_msg_event_.find(default_event);
2232  if (it == map_msg_event_.end())
2233  {
2234  map_msg_event_.insert(std::pair<std::string, ros::Publisher>(
2235  default_event,
2236  nh_.advertise<omronsentech_camera::Event>(default_event,
2237  queue_size_)));
2238  map_msg_event_[default_event].publish(msg);
2239  }
2240  else
2241  {
2242  it->second.publish(msg);
2243  }
2244  }
2245 
2246 } // end of namespace stcamera
2247 
#define STSRV_G_event_node_status_list
Definition: stheader.h:224
#define TRIGGER_NAME_ERROR_STR
Definition: stheader.h:95
const std::string BAYER_GRBG8
#define STSRV_W_node_string
Definition: stheader.h:196
StApi::IStRegisteredCallbackReleasable * cb_
#define CHUNK_NOT_SUPPORTED_ERROR_STR
Definition: stheader.h:82
bool enableTriggerCallback(omronsentech_camera::EnableTrigger::Request &req, omronsentech_camera::EnableTrigger::Response &res)
const std::string BAYER_GRBG16
#define EVENT_NOT_SUPPORTED_ERROR_STR
Definition: stheader.h:99
sensor_msgs::CameraInfo getCameraInfo(void)
bool readNodeBoolCallback(omronsentech_camera::ReadNodeBool::Request &req, omronsentech_camera::ReadNodeBool::Response &res)
#define ACQ_ALREADY_ON_ERROR
Definition: stheader.h:73
bool enableChunkCallback(omronsentech_camera::EnableChunk::Request &req, omronsentech_camera::EnableChunk::Response &res)
#define ACQ_ALREADY_OFF_ERROR_STR
Definition: stheader.h:78
#define STSRV_G_enum_list
Definition: stheader.h:234
const std::string BAYER_RGGB16
bool getChunkListCallback(omronsentech_camera::GetChunkList::Request &req, omronsentech_camera::GetChunkList::Response &res)
#define RETURN_ERR(X, MSG)
bool loadCameraInfo(const std::string &url)
bool getImageAcquisitionStatusCallback(omronsentech_camera::GetImageAcquisitionStatus::Request &req, omronsentech_camera::GetImageAcquisitionStatus::Response &res)
string cmd
#define ACQ_ALREADY_OFF_ERROR
Definition: stheader.h:77
#define MODULE_ERROR
Definition: stheader.h:57
StApi::CIStDataStreamPtr tl_ds_
#define STSRV_E_event_acquisition
Definition: stheader.h:215
image_transport::CameraPublisher it_campub_
#define STSRV_E_image_acquisition
Definition: stheader.h:212
bool readNodeFloatCallback(omronsentech_camera::ReadNodeFloat::Request &req, omronsentech_camera::ReadNodeFloat::Response &res)
#define STSRV_G_image_acquisition_status
Definition: stheader.h:218
#define STMSG_chunk
Definition: stheader.h:121
StCameraInterface(StApi::IStDeviceReleasable *dev, ros::NodeHandle nh_parent, const std::string &camera_namespace, StParameter *param, uint32_t queue_size=STCAMERA_QUEUE_SIZE)
bool writeNodeStringCallback(omronsentech_camera::WriteNodeString::Request &req, omronsentech_camera::WriteNodeString::Response &res)
GenApi::INodeMap * getNodeMap(std::string &module_name)
#define STSRV_R_node_enum
Definition: stheader.h:162
bool enableEventAcquisitionCallback(omronsentech_camera::EnableEventAcquisition::Request &req, omronsentech_camera::EnableEventAcquisition::Response &res)
#define EVENT_ALREADY_OFF_ERROR
Definition: stheader.h:69
bool writeNodeIntCallback(omronsentech_camera::WriteNodeInt::Request &req, omronsentech_camera::WriteNodeInt::Response &res)
std::string getCalibrationFile(const ros::NodeHandle &nh, std::string camera_namespace)
Definition: stparameter.cpp:67
#define NODE_ERROR_STR
Definition: stheader.h:62
bool getGenICamNodeInfoCallback(omronsentech_camera::GetGenICamNodeInfo::Request &req, omronsentech_camera::GetGenICamNodeInfo::Response &res)
#define ROS_WARN(...)
bool getTriggerListCallback(omronsentech_camera::GetTriggerList::Request &req, omronsentech_camera::GetTriggerList::Response &res)
bool writeNodeEnumIntCallback(omronsentech_camera::WriteNodeEnumInt::Request &req, omronsentech_camera::WriteNodeEnumInt::Response &res)
bool writeNodeBoolCallback(omronsentech_camera::WriteNodeBool::Request &req, omronsentech_camera::WriteNodeBool::Response &res)
Base class to control a connected camera.
#define STSRV_send_soft_trigger
Definition: stheader.h:240
#define CHECK_NULLPTR(P, X, MSG)
#define CHUNK_NAME_ERROR_STR
Definition: stheader.h:86
bool validateURL(const std::string &url)
const std::string BAYER_GBRG8
#define STSRV_R_node_string
Definition: stheader.h:172
#define EVENT_ALREADY_ON_ERROR
Definition: stheader.h:65
#define EVENT_ALREADY_OFF_ERROR_STR
Definition: stheader.h:70
const std::string BAYER_GBRG16
bool getEnumListCallback(omronsentech_camera::GetEnumList::Request &req, omronsentech_camera::GetEnumList::Response &res)
void publish(const boost::shared_ptr< M > &message) const
const std::string BAYER_BGGR16
camera_info_manager::CameraInfoManager cinfo_
#define ACQ_ALREADY_ON_ERROR_STR
Definition: stheader.h:74
#define TRIGGER_NOT_SUPPORTED_ERROR_STR
Definition: stheader.h:90
bool getEventNodeStatusListCallback(omronsentech_camera::GetEventNodeStatusList::Request &req, omronsentech_camera::GetEventNodeStatusList::Response &res)
StApi::CIStDevicePtr tl_dev_
#define STSRV_R_node
Definition: stheader.h:154
uint32_t getNumSubscribers() const
#define UNKNOWN_ERROR
Definition: stheader.h:48
#define STSRV_W_node_bool
Definition: stheader.h:179
bool executeNodeCallback(omronsentech_camera::ExecuteNode::Request &req, omronsentech_camera::ExecuteNode::Response &res)
#define TRIGGER_NAME_ERROR
Definition: stheader.h:94
#define STSRV_W_node_enum_int
Definition: stheader.h:183
void publishEventDefault(omronsentech_camera::Event &msg)
#define STSRV_E_event_node
Definition: stheader.h:209
#define ROS_INFO(...)
#define STMSG_image
Definition: stheader.h:118
#define MODULE_ERROR_STR
Definition: stheader.h:58
void eventSystemCB(StApi::IStCallbackParamBase *p, void *pvContext)
bool getLastErrorCallback(omronsentech_camera::GetLastError::Request &req, omronsentech_camera::GetLastError::Response &res)
bool readNodeCallback(omronsentech_camera::ReadNode::Request &req, omronsentech_camera::ReadNode::Response &res)
bool writeNodeFloatCallback(omronsentech_camera::WriteNodeFloat::Request &req, omronsentech_camera::WriteNodeFloat::Response &res)
#define STSRV_W_node_int
Definition: stheader.h:190
#define STSRV_R_node_int
Definition: stheader.h:166
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool readNodeIntCallback(omronsentech_camera::ReadNodeInt::Request &req, omronsentech_camera::ReadNodeInt::Response &res)
#define STSRV_G_chunk_list
Definition: stheader.h:227
const std::string MONO16
#define EVENT_ALREADY_ON_ERROR_STR
Definition: stheader.h:66
bool getEventAcquisitionStatusListCallback(omronsentech_camera::GetEventAcquisitionStatusList::Request &req, omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
bool enableEventNodeCallback(omronsentech_camera::EnableEventNode::Request &req, omronsentech_camera::EnableEventNode::Response &res)
std::map< std::string, struct StCallback > MapCallback
#define STSRV_W_node_enum_str
Definition: stheader.h:187
bool sendSoftTriggerCallback(omronsentech_camera::SendSoftTrigger::Request &req, omronsentech_camera::SendSoftTrigger::Response &res)
bool writeNodeEnumStrCallback(omronsentech_camera::WriteNodeEnumStr::Request &req, omronsentech_camera::WriteNodeEnumStr::Response &res)
Base class to control a connected camera.
#define GENICAM_ERROR
Definition: stheader.h:52
#define CHUNK_NOT_SUPPORTED_ERROR
Definition: stheader.h:81
#define EVENT_NAME_ERROR
Definition: stheader.h:103
const std::string BAYER_BGGR8
const std::string camera_namespace_
bool writeNodeCallback(omronsentech_camera::WriteNode::Request &req, omronsentech_camera::WriteNode::Response &res)
#define NODE_ERROR
Definition: stheader.h:61
#define STMSG_event
Definition: stheader.h:124
#define CHUNK_NAME_ERROR
Definition: stheader.h:85
Class to handle ROS parameter.
Definition: stparameter.h:51
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
void eventDataStreamCB(StApi::IStCallbackParamBase *p, void *pvContext)
#define CATCH_COMMON_ERR()
bool enableImageAcquisitionCallback(omronsentech_camera::EnableImageAcquisition::Request &req, omronsentech_camera::EnableImageAcquisition::Response &res)
#define STSRV_W_node_command
Definition: stheader.h:199
#define STSRV_W_node
Definition: stheader.h:176
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
#define STSRV_G_trigger_list
Definition: stheader.h:230
bool readNodeEnumCallback(omronsentech_camera::ReadNodeEnum::Request &req, omronsentech_camera::ReadNodeEnum::Response &res)
static Time now()
void eventInterfaceCB(StApi::IStCallbackParamBase *p, void *pvContext)
MapCallback * getCallbackMap(std::string &module_name)
#define STSRV_W_node_float
Definition: stheader.h:193
#define TRIGGER_NOT_SUPPORTED_ERROR
Definition: stheader.h:89
const std::string BAYER_RGGB8
#define STSRV_E_trigger
Definition: stheader.h:206
bool readNodeStringCallback(omronsentech_camera::ReadNodeString::Request &req, omronsentech_camera::ReadNodeString::Response &res)
#define STSRV_R_node_bool
Definition: stheader.h:158
void eventDeviceCB(StApi::IStCallbackParamBase *p, void *pvContext)
#define EVENT_NAME_ERROR_STR
Definition: stheader.h:104
uint32_t getNumSubscribers() const
#define STSRV_G_last_error
Definition: stheader.h:243
#define STSRV_G_genicam_node_info
Definition: stheader.h:237
#define ROS_ERROR(...)
#define STSRV_G_event_acquisition_status_list
Definition: stheader.h:221
#define EVENT_NOT_SUPPORTED_ERROR
Definition: stheader.h:98
void eventGenApiNodeCB(GenApi::INode *p, void *pvContext)
bool setCameraName(const std::string &cname)
#define STSRV_R_node_float
Definition: stheader.h:169
#define STSRV_E_chunk
Definition: stheader.h:203


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