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  }
557  if (encoding.empty())
558  {
559  ROS_WARN("%s %s %d: %s: %ld: %ld x %ld: unknown encoding %d",
560  __FILE__,__func__,__LINE__,
561  camera_namespace_.c_str(),
562  p_streambuffer->GetIStStreamBufferInfo()->GetFrameID(),
563  p_stimage->GetImageWidth(),
564  p_stimage->GetImageHeight(),
565  (int)ePFNC);
566  return;
567  }
568 
569  StApi::IStPixelFormatInfo *const p_pixelformat_info =
570  StApi::GetIStPixelFormatInfo(ePFNC);
571  if (p_pixelformat_info->IsMono() || p_pixelformat_info->IsBayer())
572  {
573  //image data
574  sensor_msgs::ImagePtr image(new sensor_msgs::Image);
575  image->header.stamp = ros::Time((double)p_streambuffer
576  ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
577  image->width = p_stimage->GetImageWidth();
578  image->height = p_stimage->GetImageHeight();
579  image->step = p_stimage->GetImageLinePitch();
580  image->encoding = encoding;
581  image->is_bigendian = (p_streambuffer->GetIStStreamBufferInfo()
582  ->GetPixelEndianness() == GenTL::PIXELENDIANNESS_BIG);
583  const size_t buffer_size = image->height * image->step;
584  image->data.resize(buffer_size);
585  memcpy(&image->data[0], p_stimage->GetImageBuffer(), buffer_size);
586 
587  //camera info data
588  sensor_msgs::CameraInfoPtr ci(new sensor_msgs::CameraInfo(
589  cinfo_.getCameraInfo()));
590  ci->header.stamp = image->header.stamp;
591 
592  if (it_campub_.getNumSubscribers() > 0)
593  {
594  it_campub_.publish(image, ci);
595  }
596 
597  if (has_chunk && msg_chunk_.getNumSubscribers() > 0)
598  {
599  chunkdata.timestamp = image->header.stamp;
600  msg_chunk_.publish(chunkdata);
601  }
602  }
603  }
604  else
605  {
606  if (has_chunk && msg_chunk_.getNumSubscribers() > 0)
607  {
608  chunkdata.timestamp = ros::Time((double)p_streambuffer
609  ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
610  msg_chunk_.publish(chunkdata);
611  }
612  }
613  }
614  catch(const StApi::CStGenTLErrorException &x)
615  {
616  ROS_ERROR("%s %s %d: \n\t%s GenTL error when retrieving payload: %d %s",
617  __FILE__,__func__,__LINE__,
618  camera_namespace_.c_str(), x.GetError(), x.GetDescription());
619  }
620  catch(GenICam::GenericException &x)
621  {
622  ROS_ERROR("%s %s %d: \n\t%s GenICam error when retrieving payload: %s",
623  __FILE__,__func__,__LINE__,
624  camera_namespace_.c_str(), x.GetDescription());
625  }
626  }
627  }
628 
629  // read node
631  omronsentech_camera::ReadNode::Request &req,
632  omronsentech_camera::ReadNode::Response &res)
633  {
634  try
635  {
636  GenApi::INodeMap* mp = getNodeMap(req.module_name);
638 
639  GenApi::INode *node = mp->GetNode(
640  GenICam::gcstring(req.node_name.c_str()));
642 
643  res.interface_type = GenApi::GetInterfaceName(node).c_str();
644  switch(node->GetPrincipalInterfaceType())
645  {
646  case GenApi::intfIInteger:
647  {
648  GenApi::CIntegerPtr ptr(node);
649  res.value = ptr->ToString();
650  return true;
651  }
652  case GenApi::intfIBoolean:
653  {
654  GenApi::CBooleanPtr ptr(node);
655  res.value = ptr->ToString();
656  return true;
657  }
658  case GenApi::intfIFloat:
659  {
660  GenApi::CFloatPtr ptr(node);
661  res.value = ptr->ToString();
662  return true;
663  }
664  case GenApi::intfIString:
665  {
666  GenApi::CStringPtr ptr(node);
667  res.value = ptr->GetValue().c_str();
668  return true;
669  }
670  case GenApi::intfIRegister:
671  {
672  GenApi::CRegisterPtr ptr(node);
673  res.value = ptr->ToString();
674  return true;
675  }
676  case GenApi::intfICategory:
677  {
678  GenApi::CCategoryPtr ptr(node);
679  res.value = ptr->ToString();
680  return true;
681  }
682  case GenApi::intfIEnumeration:
683  {
684  GenApi::CEnumerationPtr ptr(node);
685  res.value = ptr->ToString();
686  return true;
687  }
688  default:
689  {
691  }
692  }
693  }
695  }
696 
698  omronsentech_camera::ReadNodeBool::Request &req,
699  omronsentech_camera::ReadNodeBool::Response &res)
700  {
701  try
702  {
703  GenApi::INodeMap *mp = getNodeMap(req.module_name);
705 
706  GenApi::INode *node = mp->GetNode(
707  GenICam::gcstring(req.node_name.c_str()));
709 
710  GenApi::CBooleanPtr ptr(node);
711  res.value = ptr->GetValue();
712  return true;
713  }
715  }
716 
718  omronsentech_camera::ReadNodeEnum::Request &req,
719  omronsentech_camera::ReadNodeEnum::Response &res)
720  {
721  try
722  {
723  GenApi::INodeMap *mp = getNodeMap(req.module_name);
725 
726  GenApi::INode *node = mp->GetNode(
727  GenICam::gcstring(req.node_name.c_str()));
729 
730  GenApi::CEnumerationPtr ptr(node);
731  res.value_int = ptr->GetIntValue();
732  res.value_str = ptr->GetEntry(res.value_int)->GetSymbolic();
733  return true;
734  }
736  }
737 
739  omronsentech_camera::ReadNodeInt::Request &req,
740  omronsentech_camera::ReadNodeInt::Response &res)
741  {
742  try
743  {
744  GenApi::INodeMap *mp = getNodeMap(req.module_name);
746 
747  GenApi::INode *node = mp->GetNode(
748  GenICam::gcstring(req.node_name.c_str()));
750 
751  GenApi::CIntegerPtr ptr(node);
752  res.value = ptr->GetValue();
753  return true;
754  }
756  }
757 
759  omronsentech_camera::ReadNodeFloat::Request &req,
760  omronsentech_camera::ReadNodeFloat::Response &res)
761  {
762  try
763  {
764  GenApi::INodeMap *mp = getNodeMap(req.module_name);
766 
767  GenApi::INode *node = mp->GetNode(
768  GenICam::gcstring(req.node_name.c_str()));
770 
771  GenApi::CFloatPtr ptr(node);
772  res.value = ptr->GetValue();
773  return true;
774  }
776  }
777 
779  omronsentech_camera::ReadNodeString::Request &req,
780  omronsentech_camera::ReadNodeString::Response &res)
781  {
782  try
783  {
784  GenApi::INodeMap *mp = getNodeMap(req.module_name);
786 
787  GenApi::INode *node = mp->GetNode(
788  GenICam::gcstring(req.node_name.c_str()));
790 
791  GenApi::CStringPtr ptr(node);
792  res.value = ptr->GetValue();
793  return true;
794  }
796  }
797 
798  // write node
800  omronsentech_camera::WriteNode::Request &req,
801  omronsentech_camera::WriteNode::Response &res)
802  {
803  try
804  {
805  GenApi::INodeMap *mp = getNodeMap(req.module_name);
807 
808  GenApi::INode *node = mp->GetNode(
809  GenICam::gcstring(req.node_name.c_str()));
811 
812  switch(node->GetPrincipalInterfaceType())
813  {
814  case GenApi::intfIInteger:
815  {
816  GenApi::CIntegerPtr ptr(node);
817  ptr->SetValue(std::stoi(req.value));
818  return true;
819  }
820  case GenApi::intfIBoolean:
821  {
822  GenApi::CBooleanPtr ptr(node);
823  std::string true_str = "true";
824  std::string false_str = "false";
825  bool true_value = false;
826  bool false_value = false;
827  if (req.value.size() == true_str.size())
828  {
829  true_value = true;
830  for (std::string::const_iterator c1 = true_str.begin(),
831  c2 = req.value.begin(); c1 != true_str.end(); ++c1, ++c2)
832  {
833  if (tolower(*c1) != tolower(*c2))
834  {
835  true_value = false;
836  break;
837  }
838  }
839  if (true_value)
840  {
841  ptr->SetValue(true);
842  return true;
843  }
844  }
845  if (req.value.size() == false_str.size())
846  {
847  false_value = true;
848  for (std::string::const_iterator c1 = false_str.begin(),
849  c2 = req.value.begin(); c1 != false_str.end(); ++c1, ++c2)
850  {
851  if (tolower(*c1) != tolower(*c2))
852  {
853  false_value = false;
854  break;
855  }
856  }
857  if (false_value)
858  {
859  ptr->SetValue(false);
860  return true;
861  }
862  }
864  }
865  case GenApi::intfIFloat:
866  {
867  GenApi::CFloatPtr ptr(node);
868  ptr->SetValue(std::stod(req.value));
869  return true;
870  }
871  case GenApi::intfIString:
872  {
873  GenApi::CStringPtr ptr(node);
874  ptr->SetValue(GenICam::gcstring(req.value.c_str()));
875  return true;
876  }
877  case GenApi::intfIEnumeration:
878  {
879  GenApi::CEnumerationPtr ptr(node);
880  GenApi::CEnumEntryPtr enum_entry(
881  ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
882  ptr->SetIntValue(enum_entry->GetValue());
883  return true;
884  }
885  default:
886  {
888  }
889  }
890  }
892  }
893 
895  omronsentech_camera::WriteNodeBool::Request &req,
896  omronsentech_camera::WriteNodeBool::Response &res)
897  {
898  try
899  {
900  GenApi::INodeMap *mp = getNodeMap(req.module_name);
902 
903  GenApi::INode *node = mp->GetNode(
904  GenICam::gcstring(req.node_name.c_str()));
906 
907  GenApi::CBooleanPtr ptr(node);
908  ptr->SetValue(req.value);
909  return true;
910  }
912  }
913 
915  omronsentech_camera::WriteNodeEnumInt::Request &req,
916  omronsentech_camera::WriteNodeEnumInt::Response &res)
917  {
918  try
919  {
920  GenApi::INodeMap *mp = getNodeMap(req.module_name);
922 
923  GenApi::INode *node = mp->GetNode(
924  GenICam::gcstring(req.node_name.c_str()));
926 
927  GenApi::CEnumerationPtr ptr(node);
928  ptr->SetIntValue(req.value);
929  return true;
930  }
932  }
933 
935  omronsentech_camera::WriteNodeEnumStr::Request &req,
936  omronsentech_camera::WriteNodeEnumStr::Response &res)
937  {
938  try
939  {
940  GenApi::INodeMap *mp = getNodeMap(req.module_name);
942 
943  GenApi::INode *node = mp->GetNode(
944  GenICam::gcstring(req.node_name.c_str()));
946 
947  GenApi::CEnumerationPtr ptr(node);
948  GenApi::CEnumEntryPtr enum_entry(
949  ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
950  ptr->SetIntValue(enum_entry->GetValue());
951  return true;
952  }
954  }
955 
957  omronsentech_camera::WriteNodeInt::Request &req,
958  omronsentech_camera::WriteNodeInt::Response &res)
959  {
960  try
961  {
962  GenApi::INodeMap *mp = getNodeMap(req.module_name);
964 
965  GenApi::INode *node = mp->GetNode(
966  GenICam::gcstring(req.node_name.c_str()));
968 
969  GenApi::CIntegerPtr ptr(node);
970  ptr->SetValue(req.value);
971  return true;
972  }
974  }
975 
977  omronsentech_camera::WriteNodeFloat::Request &req,
978  omronsentech_camera::WriteNodeFloat::Response &res)
979  {
980  try
981  {
982  GenApi::INodeMap *mp = getNodeMap(req.module_name);
984 
985  GenApi::INode *node = mp->GetNode(
986  GenICam::gcstring(req.node_name.c_str()));
988 
989  GenApi::CFloatPtr ptr(node);
990  ptr->SetValue(req.value);
991 
992  return true;
993  }
995  }
996 
998  omronsentech_camera::WriteNodeString::Request &req,
999  omronsentech_camera::WriteNodeString::Response &res)
1000  {
1001  try
1002  {
1003  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1005 
1006  GenApi::INode *node = mp->GetNode(
1007  GenICam::gcstring(req.node_name.c_str()));
1009 
1010  GenApi::CStringPtr ptr(node);
1011 
1012  const GenICam::gcstring str = req.value.c_str();
1013  ptr->SetValue(str);
1014 
1015  return true;
1016  }
1017  CATCH_COMMON_ERR();
1018  }
1019 
1021  omronsentech_camera::ExecuteNode::Request &req,
1022  omronsentech_camera::ExecuteNode::Response &res)
1023  {
1024  try
1025  {
1026  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1028 
1029  GenApi::INode *node = mp->GetNode(
1030  GenICam::gcstring(req.node_name.c_str()));
1032 
1033  GenApi::CCommandPtr ptr(node);
1034  ptr->Execute();
1035  return true;
1036  }
1037  CATCH_COMMON_ERR();
1038  }
1039 
1040  // enable
1042  omronsentech_camera::EnableChunk::Request &req,
1043  omronsentech_camera::EnableChunk::Response &res)
1044  {
1045  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
1047  {
1049  }
1050 
1051  std::lock_guard<std::mutex> lock2(mtx_chunk_);
1052 
1053  try
1054  {
1055  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1056 
1057  GenApi::CEnumerationPtr chunk_selector(mp->GetNode(
1058  GenICam::gcstring("ChunkSelector")));
1059  GenApi::CBooleanPtr chunk_enable(mp->GetNode(
1060  GenICam::gcstring("ChunkEnable")));
1061  GenApi::CBooleanPtr chunk_active(mp->GetNode(
1062  GenICam::gcstring("ChunkModeActive")));
1063  if (!chunk_selector.IsValid() || !chunk_enable.IsValid() ||
1064  !chunk_active.IsValid())
1065  {
1067  }
1068 
1069  bool revert_chunk_mode = (false == chunk_active->GetValue());
1070  if (revert_chunk_mode)
1071  {
1072  chunk_active->SetValue(true);
1073  }
1074 
1075  if (req.chunk_name.empty()) // All chunks
1076  {
1077  GenApi::NodeList_t chunk_list;
1078  chunk_selector->GetEntries(chunk_list);
1079  for (GenApi::NodeList_t::iterator itr = chunk_list.begin();
1080  itr != chunk_list.end(); ++itr)
1081  {
1082  GenApi::CEnumEntryPtr chunk_list_entry(*itr);
1083  if (GenApi::IsAvailable(chunk_list_entry))
1084  {
1085  chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1086  if (GenApi::IsWritable(chunk_enable))
1087  {
1088  chunk_enable->SetValue(req.value);
1089  GenApi::CNodePtr chunk_value_node(mp->GetNode(
1090  "Chunk" + chunk_list_entry->GetSymbolic()));
1091  if (chunk_value_node && req.value)
1092  {
1093  MapChunk::iterator itm = map_chunk_.find(chunk_value_node
1094  ->GetName().c_str());
1095  if (itm == map_chunk_.end() || itm->second == nullptr)
1096  {
1097  map_chunk_[chunk_value_node->GetName().c_str()] =
1098  chunk_value_node;
1099  }
1100  }
1101  }
1102  }
1103  }
1104  if (!req.value)
1105  {
1106  map_chunk_.clear();
1107  chunk_active->SetValue(false);
1108  }
1109  }
1110  else
1111  {
1112  bool is_writable = true;
1113  bool all_chunk_disabled;
1114  GenApi::NodeList_t nodelist;
1115  GenApi::CEnumEntryPtr chunk_list_entry(chunk_selector
1116  ->GetEntryByName(GenICam::gcstring(req.chunk_name.c_str())));
1117  if (chunk_list_entry.IsValid() &&
1118  GenApi::IsReadable(chunk_list_entry))
1119  {
1120  chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1121  if (!GenApi::IsWritable(chunk_enable))
1122  {
1123  is_writable = false;
1124  }
1125  }
1126 
1127  if (!is_writable)
1128  {
1129  if (revert_chunk_mode)
1130  {
1131  chunk_active->SetValue(false);
1132  }
1134  }
1135 
1136  chunk_enable->SetValue(req.value);
1137 
1138  GenICam::gcstring chunk_value_name("Chunk");
1139  chunk_value_name.append(req.chunk_name.c_str());
1140  GenApi::CNodePtr chunk_value_node(mp->GetNode(chunk_value_name));
1141  if (chunk_value_node)
1142  {
1143  MapChunk::iterator itm = map_chunk_.find(chunk_value_node
1144  ->GetName().c_str());
1145  if (req.value)
1146  {
1147  if (itm == map_chunk_.end() || itm->second == nullptr)
1148  {
1149  map_chunk_[chunk_value_node->GetName().c_str()] =
1150  chunk_value_node;
1151  }
1152  }
1153  }
1154 
1155  // Disable chunk active if only Image is enabled.
1156  all_chunk_disabled = true;
1157  chunk_selector->GetEntries(nodelist);
1158  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1159  it != nodelist.end(); it++)
1160  {
1161  if (GenApi::IsAvailable(*it))
1162  {
1163  GenApi::CEnumEntryPtr enum_entry(*it);
1164  if (enum_entry->GetValue() == 0) continue; // skip image.
1165  chunk_selector->SetIntValue(enum_entry->GetValue());
1166  if (chunk_enable->GetValue() == true)
1167  {
1168  all_chunk_disabled = false;
1169  break;
1170  }
1171  }
1172  }
1173  if (all_chunk_disabled)
1174  {
1175  chunk_active->SetValue(false);
1176  }
1177  }
1178 
1179  return true;
1180  }
1181  CATCH_COMMON_ERR();
1182  }
1183 
1185  omronsentech_camera::EnableTrigger::Request &req,
1186  omronsentech_camera::EnableTrigger::Response &res)
1187  {
1188  try
1189  {
1190  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1191 
1192  // Node for selector and source
1193  GenApi::CEnumerationPtr trigger_selector(mp->GetNode(
1194  GenICam::gcstring("TriggerSelector")));
1195  GenApi::CEnumerationPtr trigger_source(mp->GetNode(
1196  GenICam::gcstring("TriggerSource")));
1197  if (!trigger_selector.IsValid() || !trigger_source.IsValid())
1198  {
1200  }
1201  GenApi::CEnumEntryPtr trigger_selector_entry(
1202  trigger_selector->GetEntryByName(
1203  GenICam::gcstring(req.trigger_selector.c_str())));
1204  GenApi::CEnumEntryPtr trigger_source_entry(
1205  trigger_source->GetEntryByName(
1206  GenICam::gcstring(req.trigger_source.c_str())));
1207  if (!trigger_selector_entry.IsValid() || !trigger_source_entry.IsValid())
1208  {
1210  }
1211 
1212  // set selector
1213  if (trigger_selector->GetIntValue() != trigger_selector_entry->GetValue())
1214  {
1215  trigger_selector->SetIntValue(trigger_selector_entry->GetValue());
1216  }
1217 
1218  // set source
1219  if (trigger_source->GetIntValue() != trigger_source_entry->GetValue())
1220  {
1221  trigger_source->SetIntValue(trigger_source_entry->GetValue());
1222  }
1223 
1224  // set delay only if supported
1225  GenApi::CFloatPtr trigger_delay = mp->GetNode(
1226  GenICam::gcstring("TriggerDelay"));
1227  if (trigger_delay.IsValid())
1228  {
1229  if (trigger_delay->GetValue() != req.trigger_delayus)
1230  {
1231  trigger_delay->SetValue(req.trigger_delayus);
1232  }
1233  }
1234 
1235  // set mode
1236  GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1237  GenICam::gcstring("TriggerMode"));
1238  if (req.value == true)
1239  {
1240  GenApi::CEnumEntryPtr trigger_mode_entry(
1241  trigger_mode->GetEntryByName(GenICam::gcstring("On")));
1242  if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1243  {
1244  trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1245  }
1246  }
1247  else
1248  {
1249  GenApi::CEnumEntryPtr trigger_mode_entry(
1250  trigger_mode->GetEntryByName(GenICam::gcstring("Off")));
1251  if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1252  {
1253  trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1254  }
1255  }
1256  return true;
1257  }
1258  CATCH_COMMON_ERR();
1259  }
1260 
1262  omronsentech_camera::EnableEventNode::Request &req,
1263  omronsentech_camera::EnableEventNode::Response &res)
1264  {
1265  std::lock_guard<std::mutex> lock(mtx_event_);
1266  try
1267  {
1268  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1270 
1271  GenApi::INode *nodeCallback = mp->GetNode(
1272  GenICam::gcstring(req.callback_node.c_str()));
1273  CHECK_NULLPTR(nodeCallback, NODE_ERROR, NODE_ERROR_STR);
1274 
1275  GenApi::CEnumerationPtr event_selector(mp->GetNode(
1276  GenICam::gcstring("EventSelector")));
1277  GenApi::CEnumerationPtr event_notif(mp->GetNode(
1278  GenICam::gcstring("EventNotification")));
1279  if (!event_selector.IsValid() || !event_notif.IsValid() ||
1280  !GenApi::IsWritable(event_selector))
1281  {
1283  }
1284 
1285  GenApi::CEnumEntryPtr enum_entry(
1286  event_selector->GetEntryByName(
1287  GenICam::gcstring(req.node_name.c_str())));
1288  if (!enum_entry.IsValid())
1289  {
1291  }
1292  event_selector->SetIntValue(enum_entry->GetValue());
1293  GenApi::CNodePtr node_callback(nodeCallback);
1294  GenICam::gcstring value = req.value ? "On" : "Off";
1295  GenApi::CEnumEntryPtr event_notif_entry(
1296  event_notif->GetEntryByName(value));
1297  if (!GenApi::IsWritable(event_notif))
1298  {
1300  }
1301  event_notif->SetIntValue(event_notif_entry->GetValue());
1302 
1303  MapCallback *cb = getCallbackMap(req.module_name);
1304  MapCallback::iterator it = cb->find(req.callback_node);
1305  std::string topic_name = STMSG_event;
1306  if (!req.event_topic_name.empty())
1307  {
1308  topic_name += "/" + req.event_topic_name;
1309  }
1310 
1311  if (req.value) // set enabled = true
1312  {
1313  if (it == cb->end()) // not found in registered list
1314  {
1315  MapPublisher::iterator itpub = map_msg_event_.find(topic_name);
1316  if (itpub == map_msg_event_.end())
1317  {
1318  map_msg_event_.insert(std::pair<std::string, ros::Publisher>(
1319  topic_name,
1320  nh_.advertise<omronsentech_camera::Event>(topic_name,
1321  queue_size_)));
1322  }
1323  struct StCallback stc;
1324  stc.topic_name_ = topic_name;
1325  stc.cb_ = StApi::RegisterCallback(node_callback, *this,
1327  (void*)(&(*cb)), GenApi::cbPostInsideLock);
1328  (*cb)[req.callback_node] = stc;
1329  return true;
1330  }
1331  // already registered
1333  }
1334 
1335  // set enabled = false
1336  if (it != cb->end()) // found in registered list
1337  {
1338  StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
1339  cbf->Release();
1340  cb->erase(it);
1341  if (topic_name.compare(std::string(camera_namespace_ +
1342  "/" + STMSG_event)) != 0) // not using default event topic
1343  {
1344  // remove publisher if no other event callback is using the topic
1345  MapCallback *cblist[5] =
1346  {
1352  };
1353  for (int i = 0; i < 5; i++)
1354  {
1355  for (MapCallback::iterator itcb = (*cblist[i]).begin();
1356  itcb != (*cblist[i]).end(); itcb++)
1357  { // if other event is using the topic, do nothing and return.
1358  if (itcb->second.topic_name_.compare(topic_name) == 0)
1359  {
1360  return true;
1361  }
1362  }
1363  }
1364  MapPublisher::iterator itpub = map_msg_event_.find(topic_name);
1365  if (itpub != map_msg_event_.end())
1366  {
1367  map_msg_event_.erase(itpub);
1368  }
1369  }
1370  return true;
1371  }
1372  // not found in registered list
1374  }
1375  CATCH_COMMON_ERR();
1376  }
1377 
1379  omronsentech_camera::EnableImageAcquisition::Request &req,
1380  omronsentech_camera::EnableImageAcquisition::Response &res)
1381  {
1382  std::lock_guard<std::mutex> lock(mtx_acquisition_);
1383  try
1384  {
1385  if (req.value == true)
1386  {
1387  //already started, return directly
1389  {
1391  }
1392 
1394  tl_ds_->StartAcquisition();
1395  tl_dev_->AcquisitionStart();
1397  return true;
1398  }
1399 
1401  {
1402  tl_dev_->AcquisitionStop();
1403  tl_ds_->StopAcquisition();
1405  return true;
1406  }
1408  }
1409  CATCH_COMMON_ERR();
1410  }
1411 
1413  omronsentech_camera::EnableEventAcquisition::Request &req,
1414  omronsentech_camera::EnableEventAcquisition::Response &res)
1415  {
1416  std::lock_guard<std::mutex> lock(mtx_event_);
1417  try
1418  {
1419  StApi::IStEventCtrl *event_control = nullptr;
1420  bool *event_value = nullptr;
1421  if (req.module_name.compare("System") == 0)
1422  {
1423  event_control = dynamic_cast<StApi::IStEventCtrl *>(
1424  tl_dev_->GetIStInterface()->GetIStSystem());
1425  event_value = &bool_event_system_;
1426  }
1427  else if (req.module_name.compare("Interface") == 0)
1428  {
1429  event_control = dynamic_cast<StApi::IStEventCtrl *>(
1430  tl_dev_->GetIStInterface());
1431  event_value = &bool_event_interface_;
1432  }
1433  else if (req.module_name.compare("LocalDevice") == 0)
1434  {
1435  event_control = dynamic_cast<StApi::IStEventCtrl *>(&(*tl_dev_));
1436  //(StApi::IStDevice*)tl_dev_);
1437  event_value = &bool_event_device_;
1438  }
1439  else if (req.module_name.compare("DataStream") == 0)
1440  {
1441  event_control = dynamic_cast<StApi::IStEventCtrl *>(&(*tl_ds_));
1442  event_value = &bool_event_datastream_;
1443  }
1444  else
1445  {
1447  }
1448 
1449  if (event_control != nullptr)
1450  {
1451  if (req.value == true) // set enable
1452  {
1453  if (req.value == *event_value)
1454  {
1456  }
1457  event_control->StartEventAcquisitionThread();
1458  *event_value = true;
1459  return true;
1460  }
1461 
1462  // set disable
1463  if (req.value == *event_value)
1464  {
1466  }
1467  event_control->StopEventAcquisitionThread();
1468  *event_value = false;
1469  return true;
1470  }
1471  }
1472  CATCH_COMMON_ERR();
1473  }
1474 
1475  // get
1477  omronsentech_camera::GetImageAcquisitionStatus::Request &req,
1478  omronsentech_camera::GetImageAcquisitionStatus::Response &res)
1479  {
1480  std::lock_guard<std::mutex> lock(mtx_acquisition_);
1481  res.value = bool_acquisition_is_started_;
1482  return true;
1483  }
1484 
1486  omronsentech_camera::GetEventAcquisitionStatusList::Request &req,
1487  omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
1488  {
1489  std::lock_guard<std::mutex> lock(mtx_event_);
1490  res.module_name_list.push_back("System");
1491  res.module_name_list.push_back("Interface");
1492  res.module_name_list.push_back("LocalDevice");
1493  res.module_name_list.push_back("RemoteDevice");
1494  res.module_name_list.push_back("DataStream");
1495  res.enabled_list.push_back(bool_event_system_);
1496  res.enabled_list.push_back(bool_event_interface_);
1497  res.enabled_list.push_back(bool_event_device_); //Local == Remote
1498  res.enabled_list.push_back(bool_event_device_); //Remote == Local
1499  res.enabled_list.push_back(bool_event_datastream_);
1500  return true;
1501  }
1502 
1504  omronsentech_camera::GetEventNodeStatusList::Request &req,
1505  omronsentech_camera::GetEventNodeStatusList::Response &res)
1506  {
1507  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1509 
1510  try
1511  {
1512  GenApi::CEnumerationPtr event_selector(mp->GetNode(
1513  GenICam::gcstring("EventSelector")));
1514  GenApi::CEnumerationPtr event_notif(mp->GetNode(
1515  GenICam::gcstring("EventNotification")));
1516  if (!event_selector.IsValid() || !event_notif.IsValid())
1517  {
1519  }
1520  if (GenApi::IsReadable(event_selector))
1521  {
1522  GenApi::NodeList_t nodelist;
1523  event_selector->GetEntries(nodelist);
1524  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1525  it != nodelist.end(); it++)
1526  {
1527  if (!GenApi::IsAvailable(*it)) continue;
1528 
1529  GenApi::CEnumEntryPtr enum_entry(*it);
1530  event_selector->SetIntValue(enum_entry->GetValue());
1531  omronsentech_camera::GenICamEvent genicam_event;
1532  genicam_event.name = std::string(enum_entry->GetSymbolic().c_str());
1533  genicam_event.enabled = (event_notif->GetCurrentEntry()
1534  ->GetSymbolic().compare("On") == 0 ? true : false);
1535 
1536  //list the callback node:
1537  std::string nodeData = "Event" + genicam_event.name + "Data";
1538  GenApi::CNodePtr event_category_node(mp->GetNode(
1539  GenICam::gcstring(nodeData.c_str())));
1540  if (event_category_node.IsValid())
1541  {
1542  MapCallback *cb = getCallbackMap(req.module_name);
1543  GenApi::FeatureList_t features;
1544  GenApi::CCategoryPtr event_category(event_category_node);
1545  event_category->GetFeatures(features);
1546  for (GenApi::FeatureList_t::iterator it = features.begin();
1547  it != features.end(); it++)
1548  {
1549  GenApi::INode *node = (*it)->GetNode();
1550  if (!GenApi::IsImplemented(node)) continue;
1551  std::string cb_name = node->GetName().c_str();
1552  genicam_event.callback_node_list.push_back(cb_name.c_str());
1553  MapCallback::iterator itmap = cb->find(cb_name);
1554  if (itmap == cb->end() || itmap->second.cb_ == nullptr)
1555  {
1556  genicam_event.callback_enabled_list.push_back(false);
1557  }
1558  else
1559  {
1560  genicam_event.callback_enabled_list.push_back(true);
1561  }
1562  }
1563  }
1564  res.event_node_list.push_back(genicam_event);
1565  }
1566  }
1567  return true;
1568  }
1569  CATCH_COMMON_ERR();
1570  }
1571 
1573  omronsentech_camera::GetChunkList::Request &req,
1574  omronsentech_camera::GetChunkList::Response &res)
1575  {
1576  std::lock_guard<std::mutex> lock1(mtx_acquisition_);
1578  {
1580  }
1581 
1582  std::lock_guard<std::mutex> lock2(mtx_chunk_);
1583  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1584  try
1585  {
1586  GenApi::CEnumerationPtr chunk_selector = mp->GetNode(
1587  GenICam::gcstring("ChunkSelector"));
1588  GenApi::NodeList_t nodelist;
1589  if (!chunk_selector.IsValid())
1590  {
1592  }
1593 
1594  GenApi::CBooleanPtr chunk_active = mp->GetNode(
1595  GenICam::gcstring("ChunkModeActive"));
1596  bool revert_chunk_mode = (false == chunk_active->GetValue());
1597  if (revert_chunk_mode)
1598  {
1599  chunk_active->SetValue(true);
1600  }
1601  chunk_selector->GetEntries(nodelist);
1602  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1603  it != nodelist.end(); it++)
1604  {
1605  if (GenApi::IsAvailable(*it))
1606  {
1607  GenApi::CEnumEntryPtr enum_entry(*it);
1608  res.chunk_name_list.push_back(
1609  std::string(enum_entry->GetSymbolic().c_str()));
1610  chunk_selector->SetIntValue(enum_entry->GetValue());
1611  GenApi::CBooleanPtr enablePtr = mp->GetNode(
1612  GenICam::gcstring("ChunkEnable"));
1613  if (enablePtr.IsValid())
1614  {
1615  res.chunk_enabled_list.push_back(
1616  enablePtr->GetValue() ? true : false);
1617  }
1618  }
1619  }
1620  if (revert_chunk_mode)
1621  {
1622  chunk_active->SetValue(false);
1623  }
1624 
1625  return true;
1626  }
1627  CATCH_COMMON_ERR();
1628  }
1629 
1631  omronsentech_camera::GetTriggerList::Request &req,
1632  omronsentech_camera::GetTriggerList::Response &res)
1633  {
1634  try
1635  {
1636  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1637 
1638  // Node for selector and source
1639  GenApi::CEnumerationPtr enum_sel = mp->GetNode(
1640  GenICam::gcstring("TriggerSelector"));
1641  GenApi::CEnumerationPtr enum_src = mp->GetNode(
1642  GenICam::gcstring("TriggerSource"));
1643  if (!enum_sel.IsValid() || !enum_src.IsValid())
1644  {
1646  }
1647 
1648  // Iterate selector
1649  GenApi::NodeList_t nodelist;
1650  enum_sel->GetEntries(nodelist);
1651  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1652  it != nodelist.end(); it++)
1653  {
1654  if (!GenApi::IsAvailable(*it)) continue;
1655  // Get selector
1656  GenApi::CEnumEntryPtr enum_entry(*it);
1657  res.trigger_selector_list.push_back(
1658  std::string(enum_entry->GetSymbolic().c_str()));
1659  enum_sel->SetIntValue(enum_entry->GetValue());
1660 
1661  // Get mode
1662  GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1663  GenICam::gcstring("TriggerMode"));
1664  if (trigger_mode.IsValid())
1665  {
1666  res.trigger_mode_list.push_back(trigger_mode->GetCurrentEntry()
1667  ->GetSymbolic().compare("On") == 0 ? true : false);
1668  }
1669  else
1670  {
1671  res.trigger_mode_list.push_back(false);
1672  }
1673 
1674  // Get delayus
1675  GenApi::CFloatPtr trigger_delay = mp->GetNode(
1676  GenICam::gcstring("TriggerDelay"));
1677  if (trigger_mode.IsValid() && GenApi::IsReadable(trigger_delay))
1678  {
1679  res.trigger_delayus_list.push_back(trigger_delay->GetValue());
1680  }
1681  else
1682  {
1683  res.trigger_delayus_list.push_back(0);
1684  }
1685  }
1686 
1687  // Iterate source
1688  nodelist.clear();
1689  enum_src->GetEntries(nodelist);
1690  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1691  it != nodelist.end(); it++)
1692  {
1693  if (!GenApi::IsAvailable(*it)) continue;
1694  // Get source
1695  GenApi::CEnumEntryPtr enum_entry(*it);
1696  res.trigger_source_list.push_back(
1697  std::string(enum_entry->GetSymbolic().c_str()));
1698  }
1699  return true;
1700  }
1701  CATCH_COMMON_ERR();
1702  }
1703 
1705  omronsentech_camera::GetEnumList::Request &req,
1706  omronsentech_camera::GetEnumList::Response &res)
1707  {
1708  try
1709  {
1710  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1712 
1713  GenApi::INode *node = mp->GetNode(
1714  GenICam::gcstring(req.node_name.c_str()));
1716 
1717  GenApi::CEnumerationPtr ptr(node);
1718  GenApi::NodeList_t nodelist;
1719  ptr->GetEntries(nodelist);
1720  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1721  it != nodelist.end(); it++)
1722  {
1723  if (GenApi::IsAvailable(*it))
1724  {
1725  GenApi::CEnumEntryPtr enum_entry(*it);
1726  res.enum_value_int_list.push_back(enum_entry->GetValue());
1727  res.enum_value_str_list.push_back(
1728  std::string(enum_entry->GetSymbolic().c_str()));
1729  }
1730  }
1731  return true;
1732  }
1733  CATCH_COMMON_ERR();
1734  }
1735 
1737  omronsentech_camera::GetGenICamNodeInfo::Request &req,
1738  omronsentech_camera::GetGenICamNodeInfo::Response &res)
1739  {
1740  try
1741  {
1742  GenApi::INodeMap *mp = getNodeMap(req.module_name);
1744 
1745  GenApi::INode *node = mp->GetNode(
1746  GenICam::gcstring(req.node_name.c_str()));
1748 
1749  //string name
1750  res.name = node->GetName().c_str();
1751 
1752  //string description
1753  res.description = node->GetDescription().c_str();
1754 
1755  //string name_space
1756  GenApi::ENameSpace genicam_namespace = node->GetNameSpace();
1757  switch(genicam_namespace)
1758  {
1759  case(GenApi::Custom):
1760  res.name_space = "Custom";
1761  break;
1762  case(GenApi::Standard):
1763  res.name_space= "Standard";
1764  break;
1765  case(GenApi::_UndefinedNameSpace):
1766  default:
1767  res.name_space = "";
1768  break;
1769  }
1770 
1771  //string interface_type
1772  res.interface_type = GenApi::GetInterfaceName(node).c_str();
1773 
1774  //string access_mode
1775  GenApi::EAccessMode genicam_accessmode = node->GetAccessMode();
1776  switch(genicam_accessmode)
1777  {
1778  case(GenApi::NI):
1779  res.access_mode = "Not implemented";
1780  break;
1781  case(GenApi::NA):
1782  res.access_mode = "Not available";
1783  break;
1784  case(GenApi::WO):
1785  res.access_mode = "Write Only";
1786  break;
1787  case(GenApi::RO):
1788  res.access_mode = "Read Only";
1789  break;
1790  case(GenApi::RW):
1791  res.access_mode = "Read and Write";
1792  break;
1793  case(GenApi::_CycleDetectAccesMode):
1794  res.access_mode = "used internally for AccessMode cycle detection";
1795  break;
1796  case(GenApi::_UndefinedAccesMode):
1797  default:
1798  res.access_mode = "";
1799  break;
1800  }
1801 
1802  //string is_cachable
1803  GenApi::EYesNo genicam_accessmode_cacheable =
1804  node->IsAccessModeCacheable();
1805  switch(genicam_accessmode_cacheable)
1806  {
1807  case(GenApi::Yes):
1808  res.is_cachable = "Yes";
1809  break;
1810  case(GenApi::No):
1811  res.is_cachable = "No";
1812  break;
1813  case(GenApi::_UndefinedYesNo):
1814  default:
1815  res.is_cachable = "";
1816  break;
1817  }
1818 
1819  //string visibility
1820  GenApi::EVisibility genicam_visibility = node->GetVisibility();
1821  switch(genicam_visibility)
1822  {
1823  case(GenApi::Beginner):
1824  res.visibility = "Beginner";
1825  break;
1826  case(GenApi::Expert):
1827  res.visibility = "Expert";
1828  break;
1829  case(GenApi::Guru):
1830  res.visibility = "Guru";
1831  break;
1832  case(GenApi::Invisible):
1833  res.visibility = "Invisible";
1834  break;
1835  case(GenApi::_UndefinedVisibility):
1836  default:
1837  res.visibility = "";
1838  }
1839 
1840  //string caching_mode
1841  GenApi::ECachingMode genicam_caching_mode = node->GetCachingMode();
1842  switch(genicam_caching_mode)
1843  {
1844  case(GenApi::NoCache):
1845  res.caching_mode = "Does not use cache";
1846  break;
1847  case(GenApi::WriteThrough):
1848  res.caching_mode = "Write to cache and register";
1849  break;
1850  case(GenApi::WriteAround):
1851  res.caching_mode = "Write to register, write to cache on read";
1852  break;
1853  case(GenApi::_UndefinedCachingMode):
1854  default:
1855  res.caching_mode = "";
1856  }
1857 
1858  //bool is_streamable
1859  res.is_streamable = node->IsStreamable() ? true : false;
1860 
1861  if (genicam_accessmode == GenApi::NA)
1862  {
1863  return true;
1864  }
1865 
1866  if (genicam_accessmode == GenApi::RW || genicam_accessmode == GenApi::RO)
1867  {
1868  switch(node->GetPrincipalInterfaceType())
1869  {
1870  case GenApi::intfIValue:
1871  {
1872  GenApi::CValuePtr ptr(node);
1873  res.current_value = ptr->ToString();
1874  break;
1875  }
1876  case GenApi::intfIInteger:
1877  {
1878  GenApi::CIntegerPtr ptr(node);
1879  res.current_value = ptr->ToString();
1880  res.min_value = std::to_string(ptr->GetMin());
1881  res.max_value = std::to_string(ptr->GetMax());
1882  res.unit = ptr->GetUnit().c_str();
1883  try
1884  {
1885  res.increment = std::to_string(ptr->GetInc());
1886  }
1887  catch(...)
1888  {
1889  res.increment = "";
1890  }
1891  break;
1892  }
1893  case GenApi::intfIBoolean:
1894  {
1895  GenApi::CBooleanPtr ptr(node);
1896  res.current_value = ptr->ToString();
1897  break;
1898  }
1899  case GenApi::intfICommand:
1900  {
1901  break;
1902  }
1903  case GenApi::intfIFloat:
1904  {
1905  GenApi::CFloatPtr ptr(node);
1906  res.current_value = ptr->ToString();
1907  res.min_value = std::to_string(ptr->GetMin());
1908  res.max_value = std::to_string(ptr->GetMax());
1909  res.unit = ptr->GetUnit().c_str();
1910  break;
1911  }
1912  case GenApi::intfIString:
1913  {
1914  GenApi::CStringPtr ptr(node);
1915  res.current_value = ptr->GetValue().c_str();
1916  break;
1917  }
1918  case GenApi::intfIRegister:
1919  {
1920  GenApi::CRegisterPtr ptr(node);
1921  res.current_value = ptr->ToString();
1922  break;
1923  }
1924  case GenApi::intfICategory:
1925  {
1926  GenApi::CCategoryPtr ptr(node);
1927  res.current_value = ptr->ToString();
1928  GenApi::FeatureList_t features;
1929  ptr->GetFeatures(features);
1930  for (GenApi::FeatureList_t::iterator it = features.begin();
1931  it != features.end(); it++)
1932  {
1933  GenApi::INode *node = (*it)->GetNode();
1934  if (!GenApi::IsImplemented(node)) continue;
1935  res.child_node_list.push_back(node->GetName().c_str());
1936  }
1937  break;
1938  }
1939  case GenApi::intfIEnumeration:
1940  {
1941  GenApi::CEnumerationPtr ptr(node);
1942  res.current_value = ptr->ToString();
1943  GenApi::NodeList_t nodelist;
1944  ptr->GetEntries(nodelist);
1945  for (GenApi::NodeList_t::iterator it = nodelist.begin();
1946  it != nodelist.end(); it++)
1947  {
1948  if (GenApi::IsAvailable(*it))
1949  {
1950  GenApi::CEnumEntryPtr enum_entry(*it);
1951  res.enum_value_int_list.push_back(enum_entry->GetValue());
1952  res.enum_value_str_list.push_back(
1953  std::string(enum_entry->GetSymbolic().c_str()));
1954  }
1955  }
1956  break;
1957  }
1958  case GenApi::intfIEnumEntry:
1959  {
1960  GenApi::CEnumEntryPtr ptr(node);
1961  res.current_value = ptr->ToString();
1962  break;
1963  }
1964  case GenApi::intfIPort:
1965  {
1966  break;
1967  }
1968  default:
1969  {
1971  }
1972  }
1973  }
1974  return true;
1975  }
1976  CATCH_COMMON_ERR();
1977  }
1978 
1980  omronsentech_camera::SendSoftTrigger::Request &req,
1981  omronsentech_camera::SendSoftTrigger::Response &res)
1982  {
1983  try
1984  {
1985  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
1986 
1987  //set selector
1988  GenApi::CEnumerationPtr enum_node = mp->GetNode(
1989  GenICam::gcstring("TriggerSelector"));
1990  GenApi::CEnumEntryPtr enum_entry(enum_node->GetEntryByName(
1991  GenICam::gcstring(req.trigger_selector.c_str())));
1992  if (enum_node->GetIntValue() != enum_entry->GetValue())
1993  {
1994  enum_node->SetIntValue(enum_entry->GetValue());
1995  }
1996 
1997  //send
1998  GenApi::CCommandPtr cmd = mp->GetNode(
1999  GenICam::gcstring("TriggerSoftware"));
2000  cmd->Execute();
2001  return true;
2002  }
2003  CATCH_COMMON_ERR();
2004  }
2005 
2007  omronsentech_camera::GetLastError::Request &req,
2008  omronsentech_camera::GetLastError::Response &res)
2009  {
2010  res.error_code = last_error_;
2011  switch(last_error_)
2012  {
2013  case 0:
2014  res.description = "No error.";
2015  return true;
2016  case UNKNOWN_ERROR:
2017  res.description = "Unknown exception occured.";
2018  return true;
2019  case GENICAM_ERROR:
2020  res.description = "Error occured when accessing GenICam code. If image acquisition is enabled, try to disable image acquisition before accessing the node.";
2021  return true;
2022  case MODULE_ERROR:
2023  res.description = "Module name is invalid. Check the list of "
2024  "module name by calling service 'get_module_list'";
2025  return true;
2026  case NODE_ERROR:
2027  res.description = "Either GenICam node name is invalid or "
2028  "the node is inaccessible.";
2029  return true;
2031  res.description = "Event already started.";
2032  return true;
2034  res.description = "Event already terminated.";
2035  return true;
2036  case ACQ_ALREADY_ON_ERROR:
2037  res.description = "Acquisition already started so that the requested "
2038  "operation cannot be processed.";
2039  return true;
2040  case ACQ_ALREADY_OFF_ERROR:
2041  res.description = "Acquisition already disabled so that the requested "
2042  "operation cannot be processed.";
2043  return true;
2045  res.description = "This device does not support chunk.";
2046  return true;
2047  case CHUNK_NAME_ERROR:
2048  res.description = "The given chunk name does not exist or not "
2049  "available.";
2050  return true;
2052  res.description = "Either trigger is not supported OR the GenICam node is non-standard. Please directly access the GenICam node.";
2053  return true;
2054  case TRIGGER_NAME_ERROR:
2055  res.description = "The given trigger selector and/or the source "
2056  "does not exist or not available.";
2057  return true;
2059  res.description = "Either Event callback is not supported or "
2060  "not available.";
2061  return true;
2062  case EVENT_NAME_ERROR:
2063  res.description = "The given event name and/or callback node "
2064  "does not exist or not available.";
2065  return true;
2066  }
2067 
2068  if ((last_error_ < -1000 && last_error_ > -1023) ||
2069  last_error_ <= -10000)
2070  {
2071  res.description = "GenTL error code. "
2072  "Please refer to GenTL documentation.";
2073  return true;
2074  }
2075  res.description = "Error code is unknown.";
2076  return true;
2077  }
2078 
2079 
2081  {
2082  // camera name
2084  {
2085  ROS_WARN("Unable to set camera name %s", camera_namespace_.c_str());
2086  }
2087 
2088  // calibration file
2089  std::string calibration_file = param_->getCalibrationFile(nh_,
2091  if (!calibration_file.empty())
2092  {
2093  ROS_INFO("Calib file %s: %s",camera_namespace_.c_str(),
2094  calibration_file.c_str());
2095  if (cinfo_.validateURL(calibration_file))
2096  {
2097  cinfo_.loadCameraInfo(calibration_file);
2098  }
2099  else
2100  {
2101  ROS_WARN("%s Invalid calibration file %s",
2102  camera_namespace_.c_str(), calibration_file.c_str());
2103  }
2104  }
2105  else
2106  {
2107  ROS_WARN("%s No calibration file found", camera_namespace_.c_str());
2108  }
2109 
2110  try
2111  {
2112  sensor_msgs::CameraInfoPtr cam_info(new sensor_msgs::CameraInfo(
2113  cinfo_.getCameraInfo()));
2114  GenApi::CNodeMapPtr mp = tl_dev_->GetRemoteIStPort()->GetINodeMap();
2115 
2116  // frame id
2117  cam_info->header.frame_id = camera_namespace_;
2118 
2119  // binning x
2120  GenApi::CIntegerPtr bin_h_val(mp->GetNode(
2121  GenICam::gcstring("DecimationHorizontal")));
2122  cam_info->binning_x = bin_h_val->GetValue();
2123 
2124  // binning y
2125  GenApi::CIntegerPtr bin_v_val(mp->GetNode(
2126  GenICam::gcstring("DecimationVertical")));
2127  cam_info->binning_y = bin_v_val->GetValue();
2128 
2129  // width
2130  GenApi::CIntegerPtr width_max_val(mp->GetNode(
2131  GenICam::gcstring("WidthMax")));
2132  cam_info->width = width_max_val->GetValue();
2133 
2134  // height
2135  GenApi::CIntegerPtr height_max_val(mp->GetNode(
2136  GenICam::gcstring("HeightMax")));
2137  cam_info->height = height_max_val->GetValue();
2138 
2139  // ROI
2140  GenApi::CNodePtr roi_node(mp->GetNode(
2141  GenICam::gcstring("RegionSelector")));
2142  if (GenApi::IsWritable(roi_node))
2143  {
2144  GenApi::CEnumerationPtr roi_val(roi_node);
2145  GenApi::CEnumEntryPtr roi_entry(roi_val->GetEntryByName(
2146  GenICam::gcstring("Region0")));
2147  roi_val->SetIntValue(roi_entry->GetValue());
2148  GenApi::CIntegerPtr width(mp->GetNode(GenICam::gcstring("Width")));
2149  GenApi::CIntegerPtr height(mp->GetNode(GenICam::gcstring("Height")));
2150  GenApi::CIntegerPtr offsetx(mp->GetNode(GenICam::gcstring("OffsetX")));
2151  GenApi::CIntegerPtr offsety(mp->GetNode(GenICam::gcstring("OffsetY")));
2152  if (GenApi::IsReadable(width))
2153  {
2154  cam_info->roi.x_offset = offsetx->GetValue();
2155  cam_info->roi.y_offset = offsety->GetValue();
2156  if (width->GetValue() != cam_info->width ||
2157  height->GetValue() != cam_info->height)
2158  {
2159  cam_info->roi.width = width->GetValue();
2160  cam_info->roi.height = height->GetValue();
2161  }
2162  }
2163  cam_info->roi.do_rectify =
2164  (cam_info->roi.width > 0 && cam_info->roi.width < cam_info->width) ||
2165  (cam_info->roi.height > 0 && cam_info->roi.height < cam_info->height);
2166  }
2167  cinfo_.setCameraInfo(*cam_info);
2168  }
2169  catch(...)
2170  {
2171  }
2172  }
2173 
2174  GenApi::INodeMap *StCameraInterface::getNodeMap(std::string &module_name)
2175  {
2176  if (module_name.compare("System") == 0)
2177  {
2178  return tl_dev_->GetIStInterface()->GetIStSystem()->GetIStPort()
2179  ->GetINodeMap();
2180  }
2181  if (module_name.compare("Interface") == 0)
2182  {
2183  return tl_dev_->GetIStInterface()->GetIStPort()->GetINodeMap();
2184  }
2185  if (module_name.compare("LocalDevice") == 0)
2186  {
2187  return tl_dev_->GetLocalIStPort()->GetINodeMap();
2188  }
2189  if (module_name.compare("RemoteDevice") == 0)
2190  {
2191  return tl_dev_->GetRemoteIStPort()->GetINodeMap();
2192  }
2193  if (module_name.compare("DataStream") == 0)
2194  {
2195  return tl_ds_->GetIStPort()->GetINodeMap();
2196  }
2197  return nullptr;
2198  }
2199 
2201  {
2202  if (module_name.compare("System") == 0)
2203  {
2204  return &map_event_system_;
2205  }
2206  if (module_name.compare("Interface") == 0)
2207  {
2208  return &map_event_interface_;
2209  }
2210  if (module_name.compare("LocalDevice") == 0)
2211  {
2212  return &map_event_localdevice_;
2213  }
2214  if (module_name.compare("RemoteDevice") == 0)
2215  {
2216  return &map_event_remotedevice_;
2217  }
2218  if (module_name.compare("DataStream") == 0)
2219  {
2220  return &map_event_datastream_;
2221  }
2222  return nullptr;
2223  }
2224 
2225  void StCameraInterface::publishEventDefault(omronsentech_camera::Event &msg)
2226  {
2227  std::string default_event = STMSG_event;
2228  MapPublisher::iterator it = map_msg_event_.find(default_event);
2229  if (it == map_msg_event_.end())
2230  {
2231  map_msg_event_.insert(std::pair<std::string, ros::Publisher>(
2232  default_event,
2233  nh_.advertise<omronsentech_camera::Event>(default_event,
2234  queue_size_)));
2235  map_msg_event_[default_event].publish(msg);
2236  }
2237  else
2238  {
2239  it->second.publish(msg);
2240  }
2241  }
2242 
2243 } // end of namespace stcamera
2244 
#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)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
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
void publish(const boost::shared_ptr< M > &message) const
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
uint32_t getNumSubscribers() const
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)
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
#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
bool writeNodeCallback(omronsentech_camera::WriteNode::Request &req, omronsentech_camera::WriteNode::Response &res)
uint32_t getNumSubscribers() const
#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
#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
#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 Jul 2 2019 19:28:17