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> 42 StApi::IStDeviceReleasable *dev,
44 const std::string &camera_namespace,
47 camera_namespace_(camera_namespace),
49 nh_(nh_parent, camera_namespace_),
53 msg_chunk_(nh_.advertise<omronsentech_camera::Chunk>(
55 queue_size_(queue_size),
56 it_campub_(it_.advertiseCamera(
std::string(
STMSG_image), queue_size)),
59 srv_read_node_bool_(nh_.advertiseService(
62 srv_read_node_enum_(nh_.advertiseService(
65 srv_read_node_int_(nh_.advertiseService(
68 srv_read_node_float_(nh_.advertiseService(
71 srv_read_node_string_(nh_.advertiseService(
74 srv_write_node_(nh_.advertiseService(
77 srv_write_node_bool_(nh_.advertiseService(
80 srv_write_node_enum_int_(nh_.advertiseService(
83 srv_write_node_enum_str_(nh_.advertiseService(
86 srv_write_node_int_(nh_.advertiseService(
89 srv_write_node_float_(nh_.advertiseService(
92 srv_write_node_string_(nh_.advertiseService(
95 srv_execute_node_(nh_.advertiseService(
98 srv_enable_chunk_(nh_.advertiseService(
101 srv_enable_trigger_(nh_.advertiseService(
104 srv_enable_event_node_(nh_.advertiseService(
107 srv_enable_image_acquisition_(nh_.advertiseService(
110 srv_enable_event_acquisition_(nh_.advertiseService(
113 srv_get_image_acquisition_status_(nh_.advertiseService(
116 srv_get_event_acquisition_status_list_(nh_.advertiseService(
119 srv_get_event_node_status_list_(nh_.advertiseService(
122 srv_get_chunk_list_(nh_.advertiseService(
125 srv_get_trigger_list_(nh_.advertiseService(
128 srv_get_enum_list_(nh_.advertiseService(
131 srv_get_genicam_node_info_(nh_.advertiseService(
134 srv_send_soft_trigger_(nh_.advertiseService(
137 srv_get_last_error_(nh_.advertiseService(
140 bool_event_system_(false),
141 bool_event_interface_(false),
142 bool_event_device_(false),
143 bool_event_datastream_(false),
148 std::lock_guard<std::mutex> lock2(
mtx_event_);
149 std::lock_guard<std::mutex> lock3(
mtx_chunk_);
155 nh_.
advertise<omronsentech_camera::Event>(default_event, queue_size)));
159 StApi::RegisterCallback(
tl_ds_, *
this,
163 StApi::RegisterCallback(
tl_dev_, *
this,
166 StApi::RegisterCallback(
tl_dev_->GetIStInterface(), *
this,
169 StApi::RegisterCallback(
tl_dev_->GetIStInterface()->GetIStSystem(), *
this,
174 if (
tl_dev_->GetIStInterface()->GetIStSystem()->GetStSystemVendor() ==
175 StApi::StSystemVendor_Sentech)
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,
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();
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)
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)
218 chunk_active->SetValue(
true);
220 chunk_selector->GetEntries(nodelist);
221 for (GenApi::NodeList_t::iterator it = nodelist.begin();
222 it != nodelist.end(); it++)
224 if (GenApi::IsAvailable(*it))
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)
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)
242 map_chunk_[p_chunk_value->GetName().c_str()] = p_chunk_value;
247 if (revert_chunk_mode)
249 chunk_active->SetValue(
false);
253 catch(GenICam::GenericException &x)
255 ROS_ERROR(
"%s %s %d: \n\t%s GenICam error when checking chunk: %s",
256 __FILE__,__func__,__LINE__,
264 tl_ds_->StartAcquisition();
284 for (
int i = 0; i < 5; i++)
287 for (MapCallback::iterator it = cb->begin(); it != cb->end(); it++)
289 StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
302 tl_ds_->StopAcquisition();
314 return (
tl_dev_->IsDeviceLost());
322 omronsentech_camera::Event msg;
324 msg.module_name =
"System";
325 if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_SystemError)
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();
340 omronsentech_camera::Event msg;
342 msg.module_name =
"Interface";
343 if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_InterfaceError)
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();
359 omronsentech_camera::Event msg;
361 msg.module_name =
"LocalDevice";
362 if (p->GetCallbackType() == StApi::StCallbackType_GenTLEvent_DeviceError)
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();
384 std::string cbModule[5] =
386 "System",
"Interface",
"LocalDevice",
"RemoteDevice",
"DataStream" 390 std::string callback_node = p->GetName().c_str();
393 for (
int i = 0; i < 5; i ++)
395 if (pvContext == (
void*)(&(*cblist[i])))
402 if (-1 == index)
return;
404 omronsentech_camera::Event msg;
406 msg.module_name = cbModule[index];
407 msg.callback_node = callback_node;
408 if (GenApi::IsReadable(p))
410 GenApi::CValuePtr pValue(p);
411 msg.event_data = pValue->ToString();
414 ((*cb)[callback_node]).topic_name_);
417 it->second.publish(msg);
427 if (p->GetCallbackType() ==
428 StApi::StCallbackType_GenTLEvent_DataStreamError)
430 omronsentech_camera::Event msg;
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();
442 if(p->GetCallbackType() ==
443 StApi::StCallbackType_GenTLEvent_DataStreamNewBuffer)
447 StApi::CIStStreamBufferPtr p_streambuffer(
tl_ds_->RetrieveBuffer(0));
455 omronsentech_camera::Chunk chunkdata;
456 bool has_chunk =
false;
460 GenApi::CNodeMapPtr cmp(p_streambuffer->GetChunkINodeMap());
461 for (MapChunk::iterator it =
map_chunk_.begin();
464 GenApi::INode *node = it->second;
465 if (node ==
nullptr)
continue;
466 switch(node->GetPrincipalInterfaceType())
468 case GenApi::intfIInteger:
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);
477 case GenApi::intfIFloat:
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);
486 case GenApi::intfIBoolean:
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);
495 case GenApi::intfIString:
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);
504 case GenApi::intfIValue:
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);
517 if (p_streambuffer->GetIStStreamBufferInfo()->IsImagePresent())
519 StApi::IStImage *p_stimage = p_streambuffer->GetIStImage();
520 const StApi::EStPixelFormatNamingConvention_t ePFNC =
521 p_stimage->GetImagePixelFormat();
523 std::string encoding =
"";
526 case StApi::StPFNC_BayerBG8:
529 case StApi::StPFNC_BayerBG16:
532 case StApi::StPFNC_BayerGB8:
535 case StApi::StPFNC_BayerGB16:
538 case StApi::StPFNC_BayerRG8:
541 case StApi::StPFNC_BayerRG16:
544 case StApi::StPFNC_BayerGR8:
547 case StApi::StPFNC_BayerGR16:
550 case StApi::StPFNC_Mono8:
553 case StApi::StPFNC_Mono16:
557 if (encoding.empty())
559 ROS_WARN(
"%s %s %d: %s: %ld: %ld x %ld: unknown encoding %d",
560 __FILE__,__func__,__LINE__,
562 p_streambuffer->GetIStStreamBufferInfo()->GetFrameID(),
563 p_stimage->GetImageWidth(),
564 p_stimage->GetImageHeight(),
569 StApi::IStPixelFormatInfo *
const p_pixelformat_info =
570 StApi::GetIStPixelFormatInfo(ePFNC);
571 if (p_pixelformat_info->IsMono() || p_pixelformat_info->IsBayer())
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);
588 sensor_msgs::CameraInfoPtr ci(
new sensor_msgs::CameraInfo(
590 ci->header.stamp = image->header.stamp;
599 chunkdata.timestamp = image->header.stamp;
608 chunkdata.timestamp =
ros::Time((
double)p_streambuffer
609 ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
614 catch(
const StApi::CStGenTLErrorException &x)
616 ROS_ERROR(
"%s %s %d: \n\t%s GenTL error when retrieving payload: %d %s",
617 __FILE__,__func__,__LINE__,
620 catch(GenICam::GenericException &x)
622 ROS_ERROR(
"%s %s %d: \n\t%s GenICam error when retrieving payload: %s",
623 __FILE__,__func__,__LINE__,
631 omronsentech_camera::ReadNode::Request &req,
632 omronsentech_camera::ReadNode::Response &res)
636 GenApi::INodeMap* mp =
getNodeMap(req.module_name);
639 GenApi::INode *node = mp->GetNode(
640 GenICam::gcstring(req.node_name.c_str()));
643 res.interface_type = GenApi::GetInterfaceName(node).c_str();
644 switch(node->GetPrincipalInterfaceType())
646 case GenApi::intfIInteger:
648 GenApi::CIntegerPtr ptr(node);
649 res.value = ptr->ToString();
652 case GenApi::intfIBoolean:
654 GenApi::CBooleanPtr ptr(node);
655 res.value = ptr->ToString();
658 case GenApi::intfIFloat:
660 GenApi::CFloatPtr ptr(node);
661 res.value = ptr->ToString();
664 case GenApi::intfIString:
666 GenApi::CStringPtr ptr(node);
667 res.value = ptr->GetValue().c_str();
670 case GenApi::intfIRegister:
672 GenApi::CRegisterPtr ptr(node);
673 res.value = ptr->ToString();
676 case GenApi::intfICategory:
678 GenApi::CCategoryPtr ptr(node);
679 res.value = ptr->ToString();
682 case GenApi::intfIEnumeration:
684 GenApi::CEnumerationPtr ptr(node);
685 res.value = ptr->ToString();
698 omronsentech_camera::ReadNodeBool::Request &req,
699 omronsentech_camera::ReadNodeBool::Response &res)
703 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
706 GenApi::INode *node = mp->GetNode(
707 GenICam::gcstring(req.node_name.c_str()));
710 GenApi::CBooleanPtr ptr(node);
711 res.value = ptr->GetValue();
718 omronsentech_camera::ReadNodeEnum::Request &req,
719 omronsentech_camera::ReadNodeEnum::Response &res)
723 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
726 GenApi::INode *node = mp->GetNode(
727 GenICam::gcstring(req.node_name.c_str()));
730 GenApi::CEnumerationPtr ptr(node);
731 res.value_int = ptr->GetIntValue();
732 res.value_str = ptr->GetEntry(res.value_int)->GetSymbolic();
739 omronsentech_camera::ReadNodeInt::Request &req,
740 omronsentech_camera::ReadNodeInt::Response &res)
744 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
747 GenApi::INode *node = mp->GetNode(
748 GenICam::gcstring(req.node_name.c_str()));
751 GenApi::CIntegerPtr ptr(node);
752 res.value = ptr->GetValue();
759 omronsentech_camera::ReadNodeFloat::Request &req,
760 omronsentech_camera::ReadNodeFloat::Response &res)
764 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
767 GenApi::INode *node = mp->GetNode(
768 GenICam::gcstring(req.node_name.c_str()));
771 GenApi::CFloatPtr ptr(node);
772 res.value = ptr->GetValue();
779 omronsentech_camera::ReadNodeString::Request &req,
780 omronsentech_camera::ReadNodeString::Response &res)
784 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
787 GenApi::INode *node = mp->GetNode(
788 GenICam::gcstring(req.node_name.c_str()));
791 GenApi::CStringPtr ptr(node);
792 res.value = ptr->GetValue();
800 omronsentech_camera::WriteNode::Request &req,
801 omronsentech_camera::WriteNode::Response &res)
805 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
808 GenApi::INode *node = mp->GetNode(
809 GenICam::gcstring(req.node_name.c_str()));
812 switch(node->GetPrincipalInterfaceType())
814 case GenApi::intfIInteger:
816 GenApi::CIntegerPtr ptr(node);
817 ptr->SetValue(std::stoi(req.value));
820 case GenApi::intfIBoolean:
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())
830 for (std::string::const_iterator c1 = true_str.begin(),
831 c2 = req.value.begin(); c1 != true_str.end(); ++c1, ++c2)
833 if (tolower(*c1) != tolower(*c2))
845 if (req.value.size() == false_str.size())
848 for (std::string::const_iterator c1 = false_str.begin(),
849 c2 = req.value.begin(); c1 != false_str.end(); ++c1, ++c2)
851 if (tolower(*c1) != tolower(*c2))
859 ptr->SetValue(
false);
865 case GenApi::intfIFloat:
867 GenApi::CFloatPtr ptr(node);
868 ptr->SetValue(std::stod(req.value));
871 case GenApi::intfIString:
873 GenApi::CStringPtr ptr(node);
874 ptr->SetValue(GenICam::gcstring(req.value.c_str()));
877 case GenApi::intfIEnumeration:
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());
895 omronsentech_camera::WriteNodeBool::Request &req,
896 omronsentech_camera::WriteNodeBool::Response &res)
900 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
903 GenApi::INode *node = mp->GetNode(
904 GenICam::gcstring(req.node_name.c_str()));
907 GenApi::CBooleanPtr ptr(node);
908 ptr->SetValue(req.value);
915 omronsentech_camera::WriteNodeEnumInt::Request &req,
916 omronsentech_camera::WriteNodeEnumInt::Response &res)
920 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
923 GenApi::INode *node = mp->GetNode(
924 GenICam::gcstring(req.node_name.c_str()));
927 GenApi::CEnumerationPtr ptr(node);
928 ptr->SetIntValue(req.value);
935 omronsentech_camera::WriteNodeEnumStr::Request &req,
936 omronsentech_camera::WriteNodeEnumStr::Response &res)
940 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
943 GenApi::INode *node = mp->GetNode(
944 GenICam::gcstring(req.node_name.c_str()));
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());
957 omronsentech_camera::WriteNodeInt::Request &req,
958 omronsentech_camera::WriteNodeInt::Response &res)
962 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
965 GenApi::INode *node = mp->GetNode(
966 GenICam::gcstring(req.node_name.c_str()));
969 GenApi::CIntegerPtr ptr(node);
970 ptr->SetValue(req.value);
977 omronsentech_camera::WriteNodeFloat::Request &req,
978 omronsentech_camera::WriteNodeFloat::Response &res)
982 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
985 GenApi::INode *node = mp->GetNode(
986 GenICam::gcstring(req.node_name.c_str()));
989 GenApi::CFloatPtr ptr(node);
990 ptr->SetValue(req.value);
998 omronsentech_camera::WriteNodeString::Request &req,
999 omronsentech_camera::WriteNodeString::Response &res)
1003 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1006 GenApi::INode *node = mp->GetNode(
1007 GenICam::gcstring(req.node_name.c_str()));
1010 GenApi::CStringPtr ptr(node);
1012 const GenICam::gcstring str = req.value.c_str();
1021 omronsentech_camera::ExecuteNode::Request &req,
1022 omronsentech_camera::ExecuteNode::Response &res)
1026 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1029 GenApi::INode *node = mp->GetNode(
1030 GenICam::gcstring(req.node_name.c_str()));
1033 GenApi::CCommandPtr ptr(node);
1042 omronsentech_camera::EnableChunk::Request &req,
1043 omronsentech_camera::EnableChunk::Response &res)
1051 std::lock_guard<std::mutex> lock2(
mtx_chunk_);
1055 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
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())
1069 bool revert_chunk_mode = (
false == chunk_active->GetValue());
1070 if (revert_chunk_mode)
1072 chunk_active->SetValue(
true);
1075 if (req.chunk_name.empty())
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)
1082 GenApi::CEnumEntryPtr chunk_list_entry(*itr);
1083 if (GenApi::IsAvailable(chunk_list_entry))
1085 chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1086 if (GenApi::IsWritable(chunk_enable))
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)
1093 MapChunk::iterator itm =
map_chunk_.find(chunk_value_node
1094 ->GetName().c_str());
1095 if (itm ==
map_chunk_.end() || itm->second ==
nullptr)
1097 map_chunk_[chunk_value_node->GetName().c_str()] =
1107 chunk_active->SetValue(
false);
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))
1120 chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1121 if (!GenApi::IsWritable(chunk_enable))
1123 is_writable =
false;
1129 if (revert_chunk_mode)
1131 chunk_active->SetValue(
false);
1136 chunk_enable->SetValue(req.value);
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)
1143 MapChunk::iterator itm =
map_chunk_.find(chunk_value_node
1144 ->GetName().c_str());
1147 if (itm ==
map_chunk_.end() || itm->second ==
nullptr)
1149 map_chunk_[chunk_value_node->GetName().c_str()] =
1156 all_chunk_disabled =
true;
1157 chunk_selector->GetEntries(nodelist);
1158 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1159 it != nodelist.end(); it++)
1161 if (GenApi::IsAvailable(*it))
1163 GenApi::CEnumEntryPtr enum_entry(*it);
1164 if (enum_entry->GetValue() == 0)
continue;
1165 chunk_selector->SetIntValue(enum_entry->GetValue());
1166 if (chunk_enable->GetValue() ==
true)
1168 all_chunk_disabled =
false;
1173 if (all_chunk_disabled)
1175 chunk_active->SetValue(
false);
1185 omronsentech_camera::EnableTrigger::Request &req,
1186 omronsentech_camera::EnableTrigger::Response &res)
1190 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
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())
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())
1213 if (trigger_selector->GetIntValue() != trigger_selector_entry->GetValue())
1215 trigger_selector->SetIntValue(trigger_selector_entry->GetValue());
1219 if (trigger_source->GetIntValue() != trigger_source_entry->GetValue())
1221 trigger_source->SetIntValue(trigger_source_entry->GetValue());
1225 GenApi::CFloatPtr trigger_delay = mp->GetNode(
1226 GenICam::gcstring(
"TriggerDelay"));
1227 if (trigger_delay.IsValid())
1229 if (trigger_delay->GetValue() != req.trigger_delayus)
1231 trigger_delay->SetValue(req.trigger_delayus);
1236 GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1237 GenICam::gcstring(
"TriggerMode"));
1238 if (req.value ==
true)
1240 GenApi::CEnumEntryPtr trigger_mode_entry(
1241 trigger_mode->GetEntryByName(GenICam::gcstring(
"On")));
1242 if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1244 trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1249 GenApi::CEnumEntryPtr trigger_mode_entry(
1250 trigger_mode->GetEntryByName(GenICam::gcstring(
"Off")));
1251 if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1253 trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1262 omronsentech_camera::EnableEventNode::Request &req,
1263 omronsentech_camera::EnableEventNode::Response &res)
1265 std::lock_guard<std::mutex> lock(
mtx_event_);
1268 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1271 GenApi::INode *nodeCallback = mp->GetNode(
1272 GenICam::gcstring(req.callback_node.c_str()));
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))
1285 GenApi::CEnumEntryPtr enum_entry(
1286 event_selector->GetEntryByName(
1287 GenICam::gcstring(req.node_name.c_str())));
1288 if (!enum_entry.IsValid())
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))
1301 event_notif->SetIntValue(event_notif_entry->GetValue());
1304 MapCallback::iterator it = cb->find(req.callback_node);
1306 if (!req.event_topic_name.empty())
1308 topic_name +=
"/" + req.event_topic_name;
1313 if (it == cb->end())
1325 stc.
cb_ = StApi::RegisterCallback(node_callback, *
this,
1327 (
void*)(&(*cb)), GenApi::cbPostInsideLock);
1328 (*cb)[req.callback_node] = stc;
1336 if (it != cb->end())
1338 StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
1353 for (
int i = 0; i < 5; i++)
1355 for (MapCallback::iterator itcb = (*cblist[i]).begin();
1356 itcb != (*cblist[i]).end(); itcb++)
1358 if (itcb->second.topic_name_.compare(topic_name) == 0)
1379 omronsentech_camera::EnableImageAcquisition::Request &req,
1380 omronsentech_camera::EnableImageAcquisition::Response &res)
1385 if (req.value ==
true)
1394 tl_ds_->StartAcquisition();
1403 tl_ds_->StopAcquisition();
1413 omronsentech_camera::EnableEventAcquisition::Request &req,
1414 omronsentech_camera::EnableEventAcquisition::Response &res)
1416 std::lock_guard<std::mutex> lock(
mtx_event_);
1419 StApi::IStEventCtrl *event_control =
nullptr;
1420 bool *event_value =
nullptr;
1421 if (req.module_name.compare(
"System") == 0)
1423 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(
1424 tl_dev_->GetIStInterface()->GetIStSystem());
1427 else if (req.module_name.compare(
"Interface") == 0)
1429 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(
1433 else if (req.module_name.compare(
"LocalDevice") == 0)
1435 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(&(*tl_dev_));
1439 else if (req.module_name.compare(
"DataStream") == 0)
1441 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(&(*tl_ds_));
1449 if (event_control !=
nullptr)
1451 if (req.value ==
true)
1453 if (req.value == *event_value)
1457 event_control->StartEventAcquisitionThread();
1458 *event_value =
true;
1463 if (req.value == *event_value)
1467 event_control->StopEventAcquisitionThread();
1468 *event_value =
false;
1477 omronsentech_camera::GetImageAcquisitionStatus::Request &req,
1478 omronsentech_camera::GetImageAcquisitionStatus::Response &res)
1486 omronsentech_camera::GetEventAcquisitionStatusList::Request &req,
1487 omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
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");
1504 omronsentech_camera::GetEventNodeStatusList::Request &req,
1505 omronsentech_camera::GetEventNodeStatusList::Response &res)
1507 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
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())
1520 if (GenApi::IsReadable(event_selector))
1522 GenApi::NodeList_t nodelist;
1523 event_selector->GetEntries(nodelist);
1524 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1525 it != nodelist.end(); it++)
1527 if (!GenApi::IsAvailable(*it))
continue;
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);
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())
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++)
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)
1556 genicam_event.callback_enabled_list.push_back(
false);
1560 genicam_event.callback_enabled_list.push_back(
true);
1564 res.event_node_list.push_back(genicam_event);
1573 omronsentech_camera::GetChunkList::Request &req,
1574 omronsentech_camera::GetChunkList::Response &res)
1582 std::lock_guard<std::mutex> lock2(
mtx_chunk_);
1583 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1586 GenApi::CEnumerationPtr chunk_selector = mp->GetNode(
1587 GenICam::gcstring(
"ChunkSelector"));
1588 GenApi::NodeList_t nodelist;
1589 if (!chunk_selector.IsValid())
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)
1599 chunk_active->SetValue(
true);
1601 chunk_selector->GetEntries(nodelist);
1602 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1603 it != nodelist.end(); it++)
1605 if (GenApi::IsAvailable(*it))
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())
1615 res.chunk_enabled_list.push_back(
1616 enablePtr->GetValue() ?
true :
false);
1620 if (revert_chunk_mode)
1622 chunk_active->SetValue(
false);
1631 omronsentech_camera::GetTriggerList::Request &req,
1632 omronsentech_camera::GetTriggerList::Response &res)
1636 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
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())
1649 GenApi::NodeList_t nodelist;
1650 enum_sel->GetEntries(nodelist);
1651 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1652 it != nodelist.end(); it++)
1654 if (!GenApi::IsAvailable(*it))
continue;
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());
1662 GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1663 GenICam::gcstring(
"TriggerMode"));
1664 if (trigger_mode.IsValid())
1666 res.trigger_mode_list.push_back(trigger_mode->GetCurrentEntry()
1667 ->GetSymbolic().compare(
"On") == 0 ?
true :
false);
1671 res.trigger_mode_list.push_back(
false);
1675 GenApi::CFloatPtr trigger_delay = mp->GetNode(
1676 GenICam::gcstring(
"TriggerDelay"));
1677 if (trigger_mode.IsValid() && GenApi::IsReadable(trigger_delay))
1679 res.trigger_delayus_list.push_back(trigger_delay->GetValue());
1683 res.trigger_delayus_list.push_back(0);
1689 enum_src->GetEntries(nodelist);
1690 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1691 it != nodelist.end(); it++)
1693 if (!GenApi::IsAvailable(*it))
continue;
1695 GenApi::CEnumEntryPtr enum_entry(*it);
1696 res.trigger_source_list.push_back(
1697 std::string(enum_entry->GetSymbolic().c_str()));
1705 omronsentech_camera::GetEnumList::Request &req,
1706 omronsentech_camera::GetEnumList::Response &res)
1710 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1713 GenApi::INode *node = mp->GetNode(
1714 GenICam::gcstring(req.node_name.c_str()));
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++)
1723 if (GenApi::IsAvailable(*it))
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()));
1737 omronsentech_camera::GetGenICamNodeInfo::Request &req,
1738 omronsentech_camera::GetGenICamNodeInfo::Response &res)
1742 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1745 GenApi::INode *node = mp->GetNode(
1746 GenICam::gcstring(req.node_name.c_str()));
1750 res.name = node->GetName().c_str();
1753 res.description = node->GetDescription().c_str();
1756 GenApi::ENameSpace genicam_namespace = node->GetNameSpace();
1757 switch(genicam_namespace)
1759 case(GenApi::Custom):
1760 res.name_space =
"Custom";
1762 case(GenApi::Standard):
1763 res.name_space=
"Standard";
1765 case(GenApi::_UndefinedNameSpace):
1767 res.name_space =
"";
1772 res.interface_type = GenApi::GetInterfaceName(node).c_str();
1775 GenApi::EAccessMode genicam_accessmode = node->GetAccessMode();
1776 switch(genicam_accessmode)
1779 res.access_mode =
"Not implemented";
1782 res.access_mode =
"Not available";
1785 res.access_mode =
"Write Only";
1788 res.access_mode =
"Read Only";
1791 res.access_mode =
"Read and Write";
1793 case(GenApi::_CycleDetectAccesMode):
1794 res.access_mode =
"used internally for AccessMode cycle detection";
1796 case(GenApi::_UndefinedAccesMode):
1798 res.access_mode =
"";
1803 GenApi::EYesNo genicam_accessmode_cacheable =
1804 node->IsAccessModeCacheable();
1805 switch(genicam_accessmode_cacheable)
1808 res.is_cachable =
"Yes";
1811 res.is_cachable =
"No";
1813 case(GenApi::_UndefinedYesNo):
1815 res.is_cachable =
"";
1820 GenApi::EVisibility genicam_visibility = node->GetVisibility();
1821 switch(genicam_visibility)
1823 case(GenApi::Beginner):
1824 res.visibility =
"Beginner";
1826 case(GenApi::Expert):
1827 res.visibility =
"Expert";
1830 res.visibility =
"Guru";
1832 case(GenApi::Invisible):
1833 res.visibility =
"Invisible";
1835 case(GenApi::_UndefinedVisibility):
1837 res.visibility =
"";
1841 GenApi::ECachingMode genicam_caching_mode = node->GetCachingMode();
1842 switch(genicam_caching_mode)
1844 case(GenApi::NoCache):
1845 res.caching_mode =
"Does not use cache";
1847 case(GenApi::WriteThrough):
1848 res.caching_mode =
"Write to cache and register";
1850 case(GenApi::WriteAround):
1851 res.caching_mode =
"Write to register, write to cache on read";
1853 case(GenApi::_UndefinedCachingMode):
1855 res.caching_mode =
"";
1859 res.is_streamable = node->IsStreamable() ?
true :
false;
1861 if (genicam_accessmode == GenApi::NA)
1866 if (genicam_accessmode == GenApi::RW || genicam_accessmode == GenApi::RO)
1868 switch(node->GetPrincipalInterfaceType())
1870 case GenApi::intfIValue:
1872 GenApi::CValuePtr ptr(node);
1873 res.current_value = ptr->ToString();
1876 case GenApi::intfIInteger:
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();
1885 res.increment = std::to_string(ptr->GetInc());
1893 case GenApi::intfIBoolean:
1895 GenApi::CBooleanPtr ptr(node);
1896 res.current_value = ptr->ToString();
1899 case GenApi::intfICommand:
1903 case GenApi::intfIFloat:
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();
1912 case GenApi::intfIString:
1914 GenApi::CStringPtr ptr(node);
1915 res.current_value = ptr->GetValue().c_str();
1918 case GenApi::intfIRegister:
1920 GenApi::CRegisterPtr ptr(node);
1921 res.current_value = ptr->ToString();
1924 case GenApi::intfICategory:
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++)
1933 GenApi::INode *node = (*it)->GetNode();
1934 if (!GenApi::IsImplemented(node))
continue;
1935 res.child_node_list.push_back(node->GetName().c_str());
1939 case GenApi::intfIEnumeration:
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++)
1948 if (GenApi::IsAvailable(*it))
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()));
1958 case GenApi::intfIEnumEntry:
1960 GenApi::CEnumEntryPtr ptr(node);
1961 res.current_value = ptr->ToString();
1964 case GenApi::intfIPort:
1980 omronsentech_camera::SendSoftTrigger::Request &req,
1981 omronsentech_camera::SendSoftTrigger::Response &res)
1985 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
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())
1994 enum_node->SetIntValue(enum_entry->GetValue());
1998 GenApi::CCommandPtr
cmd = mp->GetNode(
1999 GenICam::gcstring(
"TriggerSoftware"));
2007 omronsentech_camera::GetLastError::Request &req,
2008 omronsentech_camera::GetLastError::Response &res)
2014 res.description =
"No error.";
2017 res.description =
"Unknown exception occured.";
2020 res.description =
"Error occured when accessing GenICam code. If image acquisition is enabled, try to disable image acquisition before accessing the node.";
2023 res.description =
"Module name is invalid. Check the list of " 2024 "module name by calling service 'get_module_list'";
2027 res.description =
"Either GenICam node name is invalid or " 2028 "the node is inaccessible.";
2031 res.description =
"Event already started.";
2034 res.description =
"Event already terminated.";
2037 res.description =
"Acquisition already started so that the requested " 2038 "operation cannot be processed.";
2041 res.description =
"Acquisition already disabled so that the requested " 2042 "operation cannot be processed.";
2045 res.description =
"This device does not support chunk.";
2048 res.description =
"The given chunk name does not exist or not " 2052 res.description =
"Either trigger is not supported OR the GenICam node is non-standard. Please directly access the GenICam node.";
2055 res.description =
"The given trigger selector and/or the source " 2056 "does not exist or not available.";
2059 res.description =
"Either Event callback is not supported or " 2063 res.description =
"The given event name and/or callback node " 2064 "does not exist or not available.";
2068 if ((last_error_ < -1000 && last_error_ > -1023) ||
2071 res.description =
"GenTL error code. " 2072 "Please refer to GenTL documentation.";
2075 res.description =
"Error code is unknown.";
2091 if (!calibration_file.empty())
2094 calibration_file.c_str());
2101 ROS_WARN(
"%s Invalid calibration file %s",
2112 sensor_msgs::CameraInfoPtr cam_info(
new sensor_msgs::CameraInfo(
2114 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
2120 GenApi::CIntegerPtr bin_h_val(mp->GetNode(
2121 GenICam::gcstring(
"DecimationHorizontal")));
2122 cam_info->binning_x = bin_h_val->GetValue();
2125 GenApi::CIntegerPtr bin_v_val(mp->GetNode(
2126 GenICam::gcstring(
"DecimationVertical")));
2127 cam_info->binning_y = bin_v_val->GetValue();
2130 GenApi::CIntegerPtr width_max_val(mp->GetNode(
2131 GenICam::gcstring(
"WidthMax")));
2132 cam_info->width = width_max_val->GetValue();
2135 GenApi::CIntegerPtr height_max_val(mp->GetNode(
2136 GenICam::gcstring(
"HeightMax")));
2137 cam_info->height = height_max_val->GetValue();
2140 GenApi::CNodePtr roi_node(mp->GetNode(
2141 GenICam::gcstring(
"RegionSelector")));
2142 if (GenApi::IsWritable(roi_node))
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))
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)
2159 cam_info->roi.width = width->GetValue();
2160 cam_info->roi.height = height->GetValue();
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);
2176 if (module_name.compare(
"System") == 0)
2178 return tl_dev_->GetIStInterface()->GetIStSystem()->GetIStPort()
2181 if (module_name.compare(
"Interface") == 0)
2183 return tl_dev_->GetIStInterface()->GetIStPort()->GetINodeMap();
2185 if (module_name.compare(
"LocalDevice") == 0)
2187 return tl_dev_->GetLocalIStPort()->GetINodeMap();
2189 if (module_name.compare(
"RemoteDevice") == 0)
2191 return tl_dev_->GetRemoteIStPort()->GetINodeMap();
2193 if (module_name.compare(
"DataStream") == 0)
2195 return tl_ds_->GetIStPort()->GetINodeMap();
2202 if (module_name.compare(
"System") == 0)
2206 if (module_name.compare(
"Interface") == 0)
2210 if (module_name.compare(
"LocalDevice") == 0)
2214 if (module_name.compare(
"RemoteDevice") == 0)
2218 if (module_name.compare(
"DataStream") == 0)
2233 nh_.
advertise<omronsentech_camera::Event>(default_event,
2239 it->second.publish(msg);
#define STSRV_G_event_node_status_list
#define TRIGGER_NAME_ERROR_STR
const std::string BAYER_GRBG8
#define STSRV_W_node_string
StApi::IStRegisteredCallbackReleasable * cb_
#define CHUNK_NOT_SUPPORTED_ERROR_STR
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
sensor_msgs::CameraInfo getCameraInfo(void)
bool readNodeBoolCallback(omronsentech_camera::ReadNodeBool::Request &req, omronsentech_camera::ReadNodeBool::Response &res)
#define ACQ_ALREADY_ON_ERROR
void publish(const boost::shared_ptr< M > &message) const
bool enableChunkCallback(omronsentech_camera::EnableChunk::Request &req, omronsentech_camera::EnableChunk::Response &res)
MapCallback map_event_localdevice_
#define ACQ_ALREADY_OFF_ERROR_STR
bool bool_event_interface_
#define STSRV_G_enum_list
const std::string BAYER_RGGB16
bool getChunkListCallback(omronsentech_camera::GetChunkList::Request &req, omronsentech_camera::GetChunkList::Response &res)
#define RETURN_ERR(X, MSG)
MapCallback map_event_remotedevice_
bool loadCameraInfo(const std::string &url)
bool getImageAcquisitionStatusCallback(omronsentech_camera::GetImageAcquisitionStatus::Request &req, omronsentech_camera::GetImageAcquisitionStatus::Response &res)
#define ACQ_ALREADY_OFF_ERROR
uint32_t getNumSubscribers() const
StApi::CIStDataStreamPtr tl_ds_
#define STSRV_E_event_acquisition
image_transport::CameraPublisher it_campub_
bool bool_event_datastream_
#define STSRV_E_image_acquisition
bool readNodeFloatCallback(omronsentech_camera::ReadNodeFloat::Request &req, omronsentech_camera::ReadNodeFloat::Response &res)
#define STSRV_G_image_acquisition_status
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)
MapCallback map_event_system_
GenApi::INodeMap * getNodeMap(std::string &module_name)
virtual ~StCameraInterface()
#define STSRV_R_node_enum
bool enableEventAcquisitionCallback(omronsentech_camera::EnableEventAcquisition::Request &req, omronsentech_camera::EnableEventAcquisition::Response &res)
#define EVENT_ALREADY_OFF_ERROR
void initializeCameraInfo()
bool writeNodeIntCallback(omronsentech_camera::WriteNodeInt::Request &req, omronsentech_camera::WriteNodeInt::Response &res)
bool bool_acquisition_is_started_
std::string getCalibrationFile(const ros::NodeHandle &nh, std::string camera_namespace)
bool getGenICamNodeInfoCallback(omronsentech_camera::GetGenICamNodeInfo::Request &req, omronsentech_camera::GetGenICamNodeInfo::Response &res)
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
#define CHECK_NULLPTR(P, X, MSG)
#define CHUNK_NAME_ERROR_STR
bool validateURL(const std::string &url)
const std::string BAYER_GBRG8
#define STSRV_R_node_string
#define EVENT_ALREADY_ON_ERROR
#define EVENT_ALREADY_OFF_ERROR_STR
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
#define TRIGGER_NOT_SUPPORTED_ERROR_STR
bool getEventNodeStatusListCallback(omronsentech_camera::GetEventNodeStatusList::Request &req, omronsentech_camera::GetEventNodeStatusList::Response &res)
StApi::CIStDevicePtr tl_dev_
#define STSRV_W_node_bool
bool executeNodeCallback(omronsentech_camera::ExecuteNode::Request &req, omronsentech_camera::ExecuteNode::Response &res)
#define TRIGGER_NAME_ERROR
#define STSRV_W_node_enum_int
void publishEventDefault(omronsentech_camera::Event &msg)
#define STSRV_E_event_node
void eventSystemCB(StApi::IStCallbackParamBase *p, void *pvContext)
std::mutex mtx_acquisition_
MapCallback map_event_datastream_
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)
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
#define EVENT_ALREADY_ON_ERROR_STR
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
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 CHUNK_NOT_SUPPORTED_ERROR
const std::string BAYER_BGGR8
bool writeNodeCallback(omronsentech_camera::WriteNode::Request &req, omronsentech_camera::WriteNode::Response &res)
uint32_t getNumSubscribers() const
Class to handle ROS parameter.
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
#define STSRV_G_trigger_list
bool readNodeEnumCallback(omronsentech_camera::ReadNodeEnum::Request &req, omronsentech_camera::ReadNodeEnum::Response &res)
MapCallback map_event_interface_
ros::Publisher msg_chunk_
void eventInterfaceCB(StApi::IStCallbackParamBase *p, void *pvContext)
MapPublisher map_msg_event_
MapCallback * getCallbackMap(std::string &module_name)
#define STSRV_W_node_float
#define TRIGGER_NOT_SUPPORTED_ERROR
const std::string BAYER_RGGB8
bool readNodeStringCallback(omronsentech_camera::ReadNodeString::Request &req, omronsentech_camera::ReadNodeString::Response &res)
#define STSRV_R_node_bool
void eventDeviceCB(StApi::IStCallbackParamBase *p, void *pvContext)
#define EVENT_NAME_ERROR_STR
#define STSRV_G_last_error
#define STSRV_G_genicam_node_info
#define STSRV_G_event_acquisition_status_list
#define EVENT_NOT_SUPPORTED_ERROR
void eventGenApiNodeCB(GenApi::INode *p, void *pvContext)
bool setCameraName(const std::string &cname)
#define STSRV_R_node_float
std::string camera_namespace_