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:
556 case StApi::StPFNC_RGB8:
560 if (encoding.empty())
562 ROS_WARN(
"%s %s %d: %s: %ld: %ld x %ld: unknown encoding %d",
563 __FILE__,__func__,__LINE__,
565 p_streambuffer->GetIStStreamBufferInfo()->GetFrameID(),
566 p_stimage->GetImageWidth(),
567 p_stimage->GetImageHeight(),
572 StApi::IStPixelFormatInfo *
const p_pixelformat_info =
573 StApi::GetIStPixelFormatInfo(ePFNC);
574 if (p_pixelformat_info->IsMono() || p_pixelformat_info->IsBayer() || p_pixelformat_info->IsColor())
577 sensor_msgs::ImagePtr image(
new sensor_msgs::Image);
578 image->header.stamp =
ros::Time((
double)p_streambuffer
579 ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
581 image->width = p_stimage->GetImageWidth();
582 image->height = p_stimage->GetImageHeight();
583 image->step = p_stimage->GetImageLinePitch();
584 image->encoding = encoding;
585 image->is_bigendian = (p_streambuffer->GetIStStreamBufferInfo()
586 ->GetPixelEndianness() == GenTL::PIXELENDIANNESS_BIG);
587 const size_t buffer_size = image->height * image->step;
588 image->data.resize(buffer_size);
589 memcpy(&image->data[0], p_stimage->GetImageBuffer(), buffer_size);
592 sensor_msgs::CameraInfoPtr ci(
new sensor_msgs::CameraInfo(
594 ci->header.stamp = image->header.stamp;
602 chunkdata.timestamp = image->header.stamp;
611 chunkdata.timestamp =
ros::Time((
double)p_streambuffer
612 ->GetIStStreamBufferInfo()->GetTimestamp()/1000000.0);
617 catch(
const StApi::CStGenTLErrorException &x)
619 ROS_ERROR(
"%s %s %d: \n\t%s GenTL error when retrieving payload: %d %s",
620 __FILE__,__func__,__LINE__,
623 catch(GenICam::GenericException &x)
625 ROS_ERROR(
"%s %s %d: \n\t%s GenICam error when retrieving payload: %s",
626 __FILE__,__func__,__LINE__,
634 omronsentech_camera::ReadNode::Request &req,
635 omronsentech_camera::ReadNode::Response &res)
639 GenApi::INodeMap* mp =
getNodeMap(req.module_name);
642 GenApi::INode *node = mp->GetNode(
643 GenICam::gcstring(req.node_name.c_str()));
646 res.interface_type = GenApi::GetInterfaceName(node).c_str();
647 switch(node->GetPrincipalInterfaceType())
649 case GenApi::intfIInteger:
651 GenApi::CIntegerPtr ptr(node);
652 res.value = ptr->ToString();
655 case GenApi::intfIBoolean:
657 GenApi::CBooleanPtr ptr(node);
658 res.value = ptr->ToString();
661 case GenApi::intfIFloat:
663 GenApi::CFloatPtr ptr(node);
664 res.value = ptr->ToString();
667 case GenApi::intfIString:
669 GenApi::CStringPtr ptr(node);
670 res.value = ptr->GetValue().c_str();
673 case GenApi::intfIRegister:
675 GenApi::CRegisterPtr ptr(node);
676 res.value = ptr->ToString();
679 case GenApi::intfICategory:
681 GenApi::CCategoryPtr ptr(node);
682 res.value = ptr->ToString();
685 case GenApi::intfIEnumeration:
687 GenApi::CEnumerationPtr ptr(node);
688 res.value = ptr->ToString();
701 omronsentech_camera::ReadNodeBool::Request &req,
702 omronsentech_camera::ReadNodeBool::Response &res)
706 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
709 GenApi::INode *node = mp->GetNode(
710 GenICam::gcstring(req.node_name.c_str()));
713 GenApi::CBooleanPtr ptr(node);
714 res.value = ptr->GetValue();
721 omronsentech_camera::ReadNodeEnum::Request &req,
722 omronsentech_camera::ReadNodeEnum::Response &res)
726 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
729 GenApi::INode *node = mp->GetNode(
730 GenICam::gcstring(req.node_name.c_str()));
733 GenApi::CEnumerationPtr ptr(node);
734 res.value_int = ptr->GetIntValue();
735 res.value_str = ptr->GetEntry(res.value_int)->GetSymbolic();
742 omronsentech_camera::ReadNodeInt::Request &req,
743 omronsentech_camera::ReadNodeInt::Response &res)
747 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
750 GenApi::INode *node = mp->GetNode(
751 GenICam::gcstring(req.node_name.c_str()));
754 GenApi::CIntegerPtr ptr(node);
755 res.value = ptr->GetValue();
762 omronsentech_camera::ReadNodeFloat::Request &req,
763 omronsentech_camera::ReadNodeFloat::Response &res)
767 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
770 GenApi::INode *node = mp->GetNode(
771 GenICam::gcstring(req.node_name.c_str()));
774 GenApi::CFloatPtr ptr(node);
775 res.value = ptr->GetValue();
782 omronsentech_camera::ReadNodeString::Request &req,
783 omronsentech_camera::ReadNodeString::Response &res)
787 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
790 GenApi::INode *node = mp->GetNode(
791 GenICam::gcstring(req.node_name.c_str()));
794 GenApi::CStringPtr ptr(node);
795 res.value = ptr->GetValue();
803 omronsentech_camera::WriteNode::Request &req,
804 omronsentech_camera::WriteNode::Response &res)
808 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
811 GenApi::INode *node = mp->GetNode(
812 GenICam::gcstring(req.node_name.c_str()));
815 switch(node->GetPrincipalInterfaceType())
817 case GenApi::intfIInteger:
819 GenApi::CIntegerPtr ptr(node);
820 ptr->SetValue(std::stoi(req.value));
823 case GenApi::intfIBoolean:
825 GenApi::CBooleanPtr ptr(node);
826 std::string true_str =
"true";
827 std::string false_str =
"false";
828 bool true_value =
false;
829 bool false_value =
false;
830 if (req.value.size() == true_str.size())
833 for (std::string::const_iterator c1 = true_str.begin(),
834 c2 = req.value.begin(); c1 != true_str.end(); ++c1, ++c2)
836 if (tolower(*c1) != tolower(*c2))
848 if (req.value.size() == false_str.size())
851 for (std::string::const_iterator c1 = false_str.begin(),
852 c2 = req.value.begin(); c1 != false_str.end(); ++c1, ++c2)
854 if (tolower(*c1) != tolower(*c2))
862 ptr->SetValue(
false);
868 case GenApi::intfIFloat:
870 GenApi::CFloatPtr ptr(node);
871 ptr->SetValue(std::stod(req.value));
874 case GenApi::intfIString:
876 GenApi::CStringPtr ptr(node);
877 ptr->SetValue(GenICam::gcstring(req.value.c_str()));
880 case GenApi::intfIEnumeration:
882 GenApi::CEnumerationPtr ptr(node);
883 GenApi::CEnumEntryPtr enum_entry(
884 ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
885 ptr->SetIntValue(enum_entry->GetValue());
898 omronsentech_camera::WriteNodeBool::Request &req,
899 omronsentech_camera::WriteNodeBool::Response &res)
903 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
906 GenApi::INode *node = mp->GetNode(
907 GenICam::gcstring(req.node_name.c_str()));
910 GenApi::CBooleanPtr ptr(node);
911 ptr->SetValue(req.value);
918 omronsentech_camera::WriteNodeEnumInt::Request &req,
919 omronsentech_camera::WriteNodeEnumInt::Response &res)
923 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
926 GenApi::INode *node = mp->GetNode(
927 GenICam::gcstring(req.node_name.c_str()));
930 GenApi::CEnumerationPtr ptr(node);
931 ptr->SetIntValue(req.value);
938 omronsentech_camera::WriteNodeEnumStr::Request &req,
939 omronsentech_camera::WriteNodeEnumStr::Response &res)
943 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
946 GenApi::INode *node = mp->GetNode(
947 GenICam::gcstring(req.node_name.c_str()));
950 GenApi::CEnumerationPtr ptr(node);
951 GenApi::CEnumEntryPtr enum_entry(
952 ptr->GetEntryByName(GenICam::gcstring(req.value.c_str())));
953 ptr->SetIntValue(enum_entry->GetValue());
960 omronsentech_camera::WriteNodeInt::Request &req,
961 omronsentech_camera::WriteNodeInt::Response &res)
965 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
968 GenApi::INode *node = mp->GetNode(
969 GenICam::gcstring(req.node_name.c_str()));
972 GenApi::CIntegerPtr ptr(node);
973 ptr->SetValue(req.value);
980 omronsentech_camera::WriteNodeFloat::Request &req,
981 omronsentech_camera::WriteNodeFloat::Response &res)
985 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
988 GenApi::INode *node = mp->GetNode(
989 GenICam::gcstring(req.node_name.c_str()));
992 GenApi::CFloatPtr ptr(node);
993 ptr->SetValue(req.value);
1001 omronsentech_camera::WriteNodeString::Request &req,
1002 omronsentech_camera::WriteNodeString::Response &res)
1006 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1009 GenApi::INode *node = mp->GetNode(
1010 GenICam::gcstring(req.node_name.c_str()));
1013 GenApi::CStringPtr ptr(node);
1015 const GenICam::gcstring str = req.value.c_str();
1024 omronsentech_camera::ExecuteNode::Request &req,
1025 omronsentech_camera::ExecuteNode::Response &res)
1029 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1032 GenApi::INode *node = mp->GetNode(
1033 GenICam::gcstring(req.node_name.c_str()));
1036 GenApi::CCommandPtr ptr(node);
1045 omronsentech_camera::EnableChunk::Request &req,
1046 omronsentech_camera::EnableChunk::Response &res)
1054 std::lock_guard<std::mutex> lock2(
mtx_chunk_);
1058 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1060 GenApi::CEnumerationPtr chunk_selector(mp->GetNode(
1061 GenICam::gcstring(
"ChunkSelector")));
1062 GenApi::CBooleanPtr chunk_enable(mp->GetNode(
1063 GenICam::gcstring(
"ChunkEnable")));
1064 GenApi::CBooleanPtr chunk_active(mp->GetNode(
1065 GenICam::gcstring(
"ChunkModeActive")));
1066 if (!chunk_selector.IsValid() || !chunk_enable.IsValid() ||
1067 !chunk_active.IsValid())
1072 bool revert_chunk_mode = (
false == chunk_active->GetValue());
1073 if (revert_chunk_mode)
1075 chunk_active->SetValue(
true);
1078 if (req.chunk_name.empty())
1080 GenApi::NodeList_t chunk_list;
1081 chunk_selector->GetEntries(chunk_list);
1082 for (GenApi::NodeList_t::iterator itr = chunk_list.begin();
1083 itr != chunk_list.end(); ++itr)
1085 GenApi::CEnumEntryPtr chunk_list_entry(*itr);
1086 if (GenApi::IsAvailable(chunk_list_entry))
1088 chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1089 if (GenApi::IsWritable(chunk_enable))
1091 chunk_enable->SetValue(req.value);
1092 GenApi::CNodePtr chunk_value_node(mp->GetNode(
1093 "Chunk" + chunk_list_entry->GetSymbolic()));
1094 if (chunk_value_node && req.value)
1096 MapChunk::iterator itm =
map_chunk_.find(chunk_value_node
1097 ->GetName().c_str());
1098 if (itm ==
map_chunk_.end() || itm->second ==
nullptr)
1100 map_chunk_[chunk_value_node->GetName().c_str()] =
1110 chunk_active->SetValue(
false);
1115 bool is_writable =
true;
1116 bool all_chunk_disabled;
1117 GenApi::NodeList_t nodelist;
1118 GenApi::CEnumEntryPtr chunk_list_entry(chunk_selector
1119 ->GetEntryByName(GenICam::gcstring(req.chunk_name.c_str())));
1120 if (chunk_list_entry.IsValid() &&
1121 GenApi::IsReadable(chunk_list_entry))
1123 chunk_selector->SetIntValue(chunk_list_entry->GetValue());
1124 if (!GenApi::IsWritable(chunk_enable))
1126 is_writable =
false;
1132 if (revert_chunk_mode)
1134 chunk_active->SetValue(
false);
1139 chunk_enable->SetValue(req.value);
1141 GenICam::gcstring chunk_value_name(
"Chunk");
1142 chunk_value_name.append(req.chunk_name.c_str());
1143 GenApi::CNodePtr chunk_value_node(mp->GetNode(chunk_value_name));
1144 if (chunk_value_node)
1146 MapChunk::iterator itm =
map_chunk_.find(chunk_value_node
1147 ->GetName().c_str());
1150 if (itm ==
map_chunk_.end() || itm->second ==
nullptr)
1152 map_chunk_[chunk_value_node->GetName().c_str()] =
1159 all_chunk_disabled =
true;
1160 chunk_selector->GetEntries(nodelist);
1161 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1162 it != nodelist.end(); it++)
1164 if (GenApi::IsAvailable(*it))
1166 GenApi::CEnumEntryPtr enum_entry(*it);
1167 if (enum_entry->GetValue() == 0)
continue;
1168 chunk_selector->SetIntValue(enum_entry->GetValue());
1169 if (chunk_enable->GetValue() ==
true)
1171 all_chunk_disabled =
false;
1176 if (all_chunk_disabled)
1178 chunk_active->SetValue(
false);
1188 omronsentech_camera::EnableTrigger::Request &req,
1189 omronsentech_camera::EnableTrigger::Response &res)
1193 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1196 GenApi::CEnumerationPtr trigger_selector(mp->GetNode(
1197 GenICam::gcstring(
"TriggerSelector")));
1198 GenApi::CEnumerationPtr trigger_source(mp->GetNode(
1199 GenICam::gcstring(
"TriggerSource")));
1200 if (!trigger_selector.IsValid() || !trigger_source.IsValid())
1204 GenApi::CEnumEntryPtr trigger_selector_entry(
1205 trigger_selector->GetEntryByName(
1206 GenICam::gcstring(req.trigger_selector.c_str())));
1207 GenApi::CEnumEntryPtr trigger_source_entry(
1208 trigger_source->GetEntryByName(
1209 GenICam::gcstring(req.trigger_source.c_str())));
1210 if (!trigger_selector_entry.IsValid() || !trigger_source_entry.IsValid())
1216 if (trigger_selector->GetIntValue() != trigger_selector_entry->GetValue())
1218 trigger_selector->SetIntValue(trigger_selector_entry->GetValue());
1222 if (trigger_source->GetIntValue() != trigger_source_entry->GetValue())
1224 trigger_source->SetIntValue(trigger_source_entry->GetValue());
1228 GenApi::CFloatPtr trigger_delay = mp->GetNode(
1229 GenICam::gcstring(
"TriggerDelay"));
1230 if (trigger_delay.IsValid())
1232 if (trigger_delay->GetValue() != req.trigger_delayus)
1234 trigger_delay->SetValue(req.trigger_delayus);
1239 GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1240 GenICam::gcstring(
"TriggerMode"));
1241 if (req.value ==
true)
1243 GenApi::CEnumEntryPtr trigger_mode_entry(
1244 trigger_mode->GetEntryByName(GenICam::gcstring(
"On")));
1245 if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1247 trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1252 GenApi::CEnumEntryPtr trigger_mode_entry(
1253 trigger_mode->GetEntryByName(GenICam::gcstring(
"Off")));
1254 if (trigger_mode->GetIntValue() != trigger_mode_entry->GetValue())
1256 trigger_mode->SetIntValue(trigger_mode_entry->GetValue());
1265 omronsentech_camera::EnableEventNode::Request &req,
1266 omronsentech_camera::EnableEventNode::Response &res)
1268 std::lock_guard<std::mutex> lock(
mtx_event_);
1271 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1274 GenApi::INode *nodeCallback = mp->GetNode(
1275 GenICam::gcstring(req.callback_node.c_str()));
1278 GenApi::CEnumerationPtr event_selector(mp->GetNode(
1279 GenICam::gcstring(
"EventSelector")));
1280 GenApi::CEnumerationPtr event_notif(mp->GetNode(
1281 GenICam::gcstring(
"EventNotification")));
1282 if (!event_selector.IsValid() || !event_notif.IsValid() ||
1283 !GenApi::IsWritable(event_selector))
1288 GenApi::CEnumEntryPtr enum_entry(
1289 event_selector->GetEntryByName(
1290 GenICam::gcstring(req.node_name.c_str())));
1291 if (!enum_entry.IsValid())
1295 event_selector->SetIntValue(enum_entry->GetValue());
1296 GenApi::CNodePtr node_callback(nodeCallback);
1297 GenICam::gcstring value = req.value ?
"On" :
"Off";
1298 GenApi::CEnumEntryPtr event_notif_entry(
1299 event_notif->GetEntryByName(value));
1300 if (!GenApi::IsWritable(event_notif))
1304 event_notif->SetIntValue(event_notif_entry->GetValue());
1307 MapCallback::iterator it = cb->find(req.callback_node);
1309 if (!req.event_topic_name.empty())
1311 topic_name +=
"/" + req.event_topic_name;
1316 if (it == cb->end())
1328 stc.
cb_ = StApi::RegisterCallback(node_callback, *
this,
1330 (
void*)(&(*cb)), GenApi::cbPostInsideLock);
1331 (*cb)[req.callback_node] = stc;
1339 if (it != cb->end())
1341 StApi::IStRegisteredCallbackReleasable *cbf = it->second.cb_;
1356 for (
int i = 0; i < 5; i++)
1358 for (MapCallback::iterator itcb = (*cblist[i]).begin();
1359 itcb != (*cblist[i]).end(); itcb++)
1361 if (itcb->second.topic_name_.compare(topic_name) == 0)
1382 omronsentech_camera::EnableImageAcquisition::Request &req,
1383 omronsentech_camera::EnableImageAcquisition::Response &res)
1388 if (req.value ==
true)
1397 tl_ds_->StartAcquisition();
1406 tl_ds_->StopAcquisition();
1416 omronsentech_camera::EnableEventAcquisition::Request &req,
1417 omronsentech_camera::EnableEventAcquisition::Response &res)
1419 std::lock_guard<std::mutex> lock(
mtx_event_);
1422 StApi::IStEventCtrl *event_control =
nullptr;
1423 bool *event_value =
nullptr;
1424 if (req.module_name.compare(
"System") == 0)
1426 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(
1427 tl_dev_->GetIStInterface()->GetIStSystem());
1430 else if (req.module_name.compare(
"Interface") == 0)
1432 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(
1436 else if (req.module_name.compare(
"LocalDevice") == 0)
1438 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(&(*tl_dev_));
1442 else if (req.module_name.compare(
"DataStream") == 0)
1444 event_control =
dynamic_cast<StApi::IStEventCtrl *
>(&(*tl_ds_));
1452 if (event_control !=
nullptr)
1454 if (req.value ==
true)
1456 if (req.value == *event_value)
1460 event_control->StartEventAcquisitionThread();
1461 *event_value =
true;
1466 if (req.value == *event_value)
1470 event_control->StopEventAcquisitionThread();
1471 *event_value =
false;
1480 omronsentech_camera::GetImageAcquisitionStatus::Request &req,
1481 omronsentech_camera::GetImageAcquisitionStatus::Response &res)
1489 omronsentech_camera::GetEventAcquisitionStatusList::Request &req,
1490 omronsentech_camera::GetEventAcquisitionStatusList::Response &res)
1492 std::lock_guard<std::mutex> lock(
mtx_event_);
1493 res.module_name_list.push_back(
"System");
1494 res.module_name_list.push_back(
"Interface");
1495 res.module_name_list.push_back(
"LocalDevice");
1496 res.module_name_list.push_back(
"RemoteDevice");
1497 res.module_name_list.push_back(
"DataStream");
1507 omronsentech_camera::GetEventNodeStatusList::Request &req,
1508 omronsentech_camera::GetEventNodeStatusList::Response &res)
1510 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1515 GenApi::CEnumerationPtr event_selector(mp->GetNode(
1516 GenICam::gcstring(
"EventSelector")));
1517 GenApi::CEnumerationPtr event_notif(mp->GetNode(
1518 GenICam::gcstring(
"EventNotification")));
1519 if (!event_selector.IsValid() || !event_notif.IsValid())
1523 if (GenApi::IsReadable(event_selector))
1525 GenApi::NodeList_t nodelist;
1526 event_selector->GetEntries(nodelist);
1527 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1528 it != nodelist.end(); it++)
1530 if (!GenApi::IsAvailable(*it))
continue;
1532 GenApi::CEnumEntryPtr enum_entry(*it);
1533 event_selector->SetIntValue(enum_entry->GetValue());
1534 omronsentech_camera::GenICamEvent genicam_event;
1535 genicam_event.name = std::string(enum_entry->GetSymbolic().c_str());
1536 genicam_event.enabled = (event_notif->GetCurrentEntry()
1537 ->GetSymbolic().compare(
"On") == 0 ? true :
false);
1540 std::string nodeData =
"Event" + genicam_event.name +
"Data";
1541 GenApi::CNodePtr event_category_node(mp->GetNode(
1542 GenICam::gcstring(nodeData.c_str())));
1543 if (event_category_node.IsValid())
1546 GenApi::FeatureList_t features;
1547 GenApi::CCategoryPtr event_category(event_category_node);
1548 event_category->GetFeatures(features);
1549 for (GenApi::FeatureList_t::iterator it = features.begin();
1550 it != features.end(); it++)
1552 GenApi::INode *node = (*it)->GetNode();
1553 if (!GenApi::IsImplemented(node))
continue;
1554 std::string cb_name = node->GetName().c_str();
1555 genicam_event.callback_node_list.push_back(cb_name.c_str());
1556 MapCallback::iterator itmap = cb->find(cb_name);
1557 if (itmap == cb->end() || itmap->second.cb_ ==
nullptr)
1559 genicam_event.callback_enabled_list.push_back(
false);
1563 genicam_event.callback_enabled_list.push_back(
true);
1567 res.event_node_list.push_back(genicam_event);
1576 omronsentech_camera::GetChunkList::Request &req,
1577 omronsentech_camera::GetChunkList::Response &res)
1585 std::lock_guard<std::mutex> lock2(
mtx_chunk_);
1586 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1589 GenApi::CEnumerationPtr chunk_selector = mp->GetNode(
1590 GenICam::gcstring(
"ChunkSelector"));
1591 GenApi::NodeList_t nodelist;
1592 if (!chunk_selector.IsValid())
1597 GenApi::CBooleanPtr chunk_active = mp->GetNode(
1598 GenICam::gcstring(
"ChunkModeActive"));
1599 bool revert_chunk_mode = (
false == chunk_active->GetValue());
1600 if (revert_chunk_mode)
1602 chunk_active->SetValue(
true);
1604 chunk_selector->GetEntries(nodelist);
1605 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1606 it != nodelist.end(); it++)
1608 if (GenApi::IsAvailable(*it))
1610 GenApi::CEnumEntryPtr enum_entry(*it);
1611 res.chunk_name_list.push_back(
1612 std::string(enum_entry->GetSymbolic().c_str()));
1613 chunk_selector->SetIntValue(enum_entry->GetValue());
1614 GenApi::CBooleanPtr enablePtr = mp->GetNode(
1615 GenICam::gcstring(
"ChunkEnable"));
1616 if (enablePtr.IsValid())
1618 res.chunk_enabled_list.push_back(
1619 enablePtr->GetValue() ? true :
false);
1623 if (revert_chunk_mode)
1625 chunk_active->SetValue(
false);
1634 omronsentech_camera::GetTriggerList::Request &req,
1635 omronsentech_camera::GetTriggerList::Response &res)
1639 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1642 GenApi::CEnumerationPtr enum_sel = mp->GetNode(
1643 GenICam::gcstring(
"TriggerSelector"));
1644 GenApi::CEnumerationPtr enum_src = mp->GetNode(
1645 GenICam::gcstring(
"TriggerSource"));
1646 if (!enum_sel.IsValid() || !enum_src.IsValid())
1652 GenApi::NodeList_t nodelist;
1653 enum_sel->GetEntries(nodelist);
1654 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1655 it != nodelist.end(); it++)
1657 if (!GenApi::IsAvailable(*it))
continue;
1659 GenApi::CEnumEntryPtr enum_entry(*it);
1660 res.trigger_selector_list.push_back(
1661 std::string(enum_entry->GetSymbolic().c_str()));
1662 enum_sel->SetIntValue(enum_entry->GetValue());
1665 GenApi::CEnumerationPtr trigger_mode = mp->GetNode(
1666 GenICam::gcstring(
"TriggerMode"));
1667 if (trigger_mode.IsValid())
1669 res.trigger_mode_list.push_back(trigger_mode->GetCurrentEntry()
1670 ->GetSymbolic().compare(
"On") == 0 ? true :
false);
1674 res.trigger_mode_list.push_back(
false);
1678 GenApi::CFloatPtr trigger_delay = mp->GetNode(
1679 GenICam::gcstring(
"TriggerDelay"));
1680 if (trigger_mode.IsValid() && GenApi::IsReadable(trigger_delay))
1682 res.trigger_delayus_list.push_back(trigger_delay->GetValue());
1686 res.trigger_delayus_list.push_back(0);
1692 enum_src->GetEntries(nodelist);
1693 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1694 it != nodelist.end(); it++)
1696 if (!GenApi::IsAvailable(*it))
continue;
1698 GenApi::CEnumEntryPtr enum_entry(*it);
1699 res.trigger_source_list.push_back(
1700 std::string(enum_entry->GetSymbolic().c_str()));
1708 omronsentech_camera::GetEnumList::Request &req,
1709 omronsentech_camera::GetEnumList::Response &res)
1713 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1716 GenApi::INode *node = mp->GetNode(
1717 GenICam::gcstring(req.node_name.c_str()));
1720 GenApi::CEnumerationPtr ptr(node);
1721 GenApi::NodeList_t nodelist;
1722 ptr->GetEntries(nodelist);
1723 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1724 it != nodelist.end(); it++)
1726 if (GenApi::IsAvailable(*it))
1728 GenApi::CEnumEntryPtr enum_entry(*it);
1729 res.enum_value_int_list.push_back(enum_entry->GetValue());
1730 res.enum_value_str_list.push_back(
1731 std::string(enum_entry->GetSymbolic().c_str()));
1740 omronsentech_camera::GetGenICamNodeInfo::Request &req,
1741 omronsentech_camera::GetGenICamNodeInfo::Response &res)
1745 GenApi::INodeMap *mp =
getNodeMap(req.module_name);
1748 GenApi::INode *node = mp->GetNode(
1749 GenICam::gcstring(req.node_name.c_str()));
1753 res.name = node->GetName().c_str();
1756 res.description = node->GetDescription().c_str();
1759 GenApi::ENameSpace genicam_namespace = node->GetNameSpace();
1760 switch(genicam_namespace)
1762 case(GenApi::Custom):
1763 res.name_space =
"Custom";
1765 case(GenApi::Standard):
1766 res.name_space=
"Standard";
1768 case(GenApi::_UndefinedNameSpace):
1770 res.name_space =
"";
1775 res.interface_type = GenApi::GetInterfaceName(node).c_str();
1778 GenApi::EAccessMode genicam_accessmode = node->GetAccessMode();
1779 switch(genicam_accessmode)
1782 res.access_mode =
"Not implemented";
1785 res.access_mode =
"Not available";
1788 res.access_mode =
"Write Only";
1791 res.access_mode =
"Read Only";
1794 res.access_mode =
"Read and Write";
1796 case(GenApi::_CycleDetectAccesMode):
1797 res.access_mode =
"used internally for AccessMode cycle detection";
1799 case(GenApi::_UndefinedAccesMode):
1801 res.access_mode =
"";
1806 GenApi::EYesNo genicam_accessmode_cacheable =
1807 node->IsAccessModeCacheable();
1808 switch(genicam_accessmode_cacheable)
1811 res.is_cachable =
"Yes";
1814 res.is_cachable =
"No";
1816 case(GenApi::_UndefinedYesNo):
1818 res.is_cachable =
"";
1823 GenApi::EVisibility genicam_visibility = node->GetVisibility();
1824 switch(genicam_visibility)
1826 case(GenApi::Beginner):
1827 res.visibility =
"Beginner";
1829 case(GenApi::Expert):
1830 res.visibility =
"Expert";
1833 res.visibility =
"Guru";
1835 case(GenApi::Invisible):
1836 res.visibility =
"Invisible";
1838 case(GenApi::_UndefinedVisibility):
1840 res.visibility =
"";
1844 GenApi::ECachingMode genicam_caching_mode = node->GetCachingMode();
1845 switch(genicam_caching_mode)
1847 case(GenApi::NoCache):
1848 res.caching_mode =
"Does not use cache";
1850 case(GenApi::WriteThrough):
1851 res.caching_mode =
"Write to cache and register";
1853 case(GenApi::WriteAround):
1854 res.caching_mode =
"Write to register, write to cache on read";
1856 case(GenApi::_UndefinedCachingMode):
1858 res.caching_mode =
"";
1862 res.is_streamable = node->IsStreamable() ? true :
false;
1864 if (genicam_accessmode == GenApi::NA)
1869 if (genicam_accessmode == GenApi::RW || genicam_accessmode == GenApi::RO)
1871 switch(node->GetPrincipalInterfaceType())
1873 case GenApi::intfIValue:
1875 GenApi::CValuePtr ptr(node);
1876 res.current_value = ptr->ToString();
1879 case GenApi::intfIInteger:
1881 GenApi::CIntegerPtr ptr(node);
1882 res.current_value = ptr->ToString();
1883 res.min_value = std::to_string(ptr->GetMin());
1884 res.max_value = std::to_string(ptr->GetMax());
1885 res.unit = ptr->GetUnit().c_str();
1888 res.increment = std::to_string(ptr->GetInc());
1896 case GenApi::intfIBoolean:
1898 GenApi::CBooleanPtr ptr(node);
1899 res.current_value = ptr->ToString();
1902 case GenApi::intfICommand:
1906 case GenApi::intfIFloat:
1908 GenApi::CFloatPtr ptr(node);
1909 res.current_value = ptr->ToString();
1910 res.min_value = std::to_string(ptr->GetMin());
1911 res.max_value = std::to_string(ptr->GetMax());
1912 res.unit = ptr->GetUnit().c_str();
1915 case GenApi::intfIString:
1917 GenApi::CStringPtr ptr(node);
1918 res.current_value = ptr->GetValue().c_str();
1921 case GenApi::intfIRegister:
1923 GenApi::CRegisterPtr ptr(node);
1924 res.current_value = ptr->ToString();
1927 case GenApi::intfICategory:
1929 GenApi::CCategoryPtr ptr(node);
1930 res.current_value = ptr->ToString();
1931 GenApi::FeatureList_t features;
1932 ptr->GetFeatures(features);
1933 for (GenApi::FeatureList_t::iterator it = features.begin();
1934 it != features.end(); it++)
1936 GenApi::INode *node = (*it)->GetNode();
1937 if (!GenApi::IsImplemented(node))
continue;
1938 res.child_node_list.push_back(node->GetName().c_str());
1942 case GenApi::intfIEnumeration:
1944 GenApi::CEnumerationPtr ptr(node);
1945 res.current_value = ptr->ToString();
1946 GenApi::NodeList_t nodelist;
1947 ptr->GetEntries(nodelist);
1948 for (GenApi::NodeList_t::iterator it = nodelist.begin();
1949 it != nodelist.end(); it++)
1951 if (GenApi::IsAvailable(*it))
1953 GenApi::CEnumEntryPtr enum_entry(*it);
1954 res.enum_value_int_list.push_back(enum_entry->GetValue());
1955 res.enum_value_str_list.push_back(
1956 std::string(enum_entry->GetSymbolic().c_str()));
1961 case GenApi::intfIEnumEntry:
1963 GenApi::CEnumEntryPtr ptr(node);
1964 res.current_value = ptr->ToString();
1967 case GenApi::intfIPort:
1983 omronsentech_camera::SendSoftTrigger::Request &req,
1984 omronsentech_camera::SendSoftTrigger::Response &res)
1988 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
1991 GenApi::CEnumerationPtr enum_node = mp->GetNode(
1992 GenICam::gcstring(
"TriggerSelector"));
1993 GenApi::CEnumEntryPtr enum_entry(enum_node->GetEntryByName(
1994 GenICam::gcstring(req.trigger_selector.c_str())));
1995 if (enum_node->GetIntValue() != enum_entry->GetValue())
1997 enum_node->SetIntValue(enum_entry->GetValue());
2001 GenApi::CCommandPtr
cmd = mp->GetNode(
2002 GenICam::gcstring(
"TriggerSoftware"));
2010 omronsentech_camera::GetLastError::Request &req,
2011 omronsentech_camera::GetLastError::Response &res)
2017 res.description =
"No error.";
2020 res.description =
"Unknown exception occured.";
2023 res.description =
"Error occured when accessing GenICam code. If image acquisition is enabled, try to disable image acquisition before accessing the node.";
2026 res.description =
"Module name is invalid. Check the list of " 2027 "module name by calling service 'get_module_list'";
2030 res.description =
"Either GenICam node name is invalid or " 2031 "the node is inaccessible.";
2034 res.description =
"Event already started.";
2037 res.description =
"Event already terminated.";
2040 res.description =
"Acquisition already started so that the requested " 2041 "operation cannot be processed.";
2044 res.description =
"Acquisition already disabled so that the requested " 2045 "operation cannot be processed.";
2048 res.description =
"This device does not support chunk.";
2051 res.description =
"The given chunk name does not exist or not " 2055 res.description =
"Either trigger is not supported OR the GenICam node is non-standard. Please directly access the GenICam node.";
2058 res.description =
"The given trigger selector and/or the source " 2059 "does not exist or not available.";
2062 res.description =
"Either Event callback is not supported or " 2066 res.description =
"The given event name and/or callback node " 2067 "does not exist or not available.";
2071 if ((last_error_ < -1000 && last_error_ > -1023) ||
2074 res.description =
"GenTL error code. " 2075 "Please refer to GenTL documentation.";
2078 res.description =
"Error code is unknown.";
2094 if (!calibration_file.empty())
2097 calibration_file.c_str());
2104 ROS_WARN(
"%s Invalid calibration file %s",
2115 sensor_msgs::CameraInfoPtr cam_info(
new sensor_msgs::CameraInfo(
2117 GenApi::CNodeMapPtr mp =
tl_dev_->GetRemoteIStPort()->GetINodeMap();
2123 GenApi::CIntegerPtr bin_h_val(mp->GetNode(
2124 GenICam::gcstring(
"DecimationHorizontal")));
2125 cam_info->binning_x = bin_h_val->GetValue();
2128 GenApi::CIntegerPtr bin_v_val(mp->GetNode(
2129 GenICam::gcstring(
"DecimationVertical")));
2130 cam_info->binning_y = bin_v_val->GetValue();
2133 GenApi::CIntegerPtr width_max_val(mp->GetNode(
2134 GenICam::gcstring(
"WidthMax")));
2135 cam_info->width = width_max_val->GetValue();
2138 GenApi::CIntegerPtr height_max_val(mp->GetNode(
2139 GenICam::gcstring(
"HeightMax")));
2140 cam_info->height = height_max_val->GetValue();
2143 GenApi::CNodePtr roi_node(mp->GetNode(
2144 GenICam::gcstring(
"RegionSelector")));
2145 if (GenApi::IsWritable(roi_node))
2147 GenApi::CEnumerationPtr roi_val(roi_node);
2148 GenApi::CEnumEntryPtr roi_entry(roi_val->GetEntryByName(
2149 GenICam::gcstring(
"Region0")));
2150 roi_val->SetIntValue(roi_entry->GetValue());
2151 GenApi::CIntegerPtr width(mp->GetNode(GenICam::gcstring(
"Width")));
2152 GenApi::CIntegerPtr height(mp->GetNode(GenICam::gcstring(
"Height")));
2153 GenApi::CIntegerPtr offsetx(mp->GetNode(GenICam::gcstring(
"OffsetX")));
2154 GenApi::CIntegerPtr offsety(mp->GetNode(GenICam::gcstring(
"OffsetY")));
2155 if (GenApi::IsReadable(width))
2157 cam_info->roi.x_offset = offsetx->GetValue();
2158 cam_info->roi.y_offset = offsety->GetValue();
2159 if (width->GetValue() != cam_info->width ||
2160 height->GetValue() != cam_info->height)
2162 cam_info->roi.width = width->GetValue();
2163 cam_info->roi.height = height->GetValue();
2166 cam_info->roi.do_rectify =
2167 (cam_info->roi.width > 0 && cam_info->roi.width < cam_info->width) ||
2168 (cam_info->roi.height > 0 && cam_info->roi.height < cam_info->height);
2179 if (module_name.compare(
"System") == 0)
2181 return tl_dev_->GetIStInterface()->GetIStSystem()->GetIStPort()
2184 if (module_name.compare(
"Interface") == 0)
2186 return tl_dev_->GetIStInterface()->GetIStPort()->GetINodeMap();
2188 if (module_name.compare(
"LocalDevice") == 0)
2190 return tl_dev_->GetLocalIStPort()->GetINodeMap();
2192 if (module_name.compare(
"RemoteDevice") == 0)
2194 return tl_dev_->GetRemoteIStPort()->GetINodeMap();
2196 if (module_name.compare(
"DataStream") == 0)
2198 return tl_ds_->GetIStPort()->GetINodeMap();
2205 if (module_name.compare(
"System") == 0)
2209 if (module_name.compare(
"Interface") == 0)
2213 if (module_name.compare(
"LocalDevice") == 0)
2217 if (module_name.compare(
"RemoteDevice") == 0)
2221 if (module_name.compare(
"DataStream") == 0)
2236 nh_.
advertise<omronsentech_camera::Event>(default_event,
2242 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)
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
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
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)
void publish(const boost::shared_ptr< M > &message) const
const std::string BAYER_BGGR16
camera_info_manager::CameraInfoManager cinfo_
#define ACQ_ALREADY_ON_ERROR_STR
#define TRIGGER_NOT_SUPPORTED_ERROR_STR
bool getEventNodeStatusListCallback(omronsentech_camera::GetEventNodeStatusList::Request &req, omronsentech_camera::GetEventNodeStatusList::Response &res)
StApi::CIStDevicePtr tl_dev_
uint32_t getNumSubscribers() const
#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
const std::string camera_namespace_
bool writeNodeCallback(omronsentech_camera::WriteNode::Request &req, omronsentech_camera::WriteNode::Response &res)
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
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
#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
uint32_t getNumSubscribers() const
#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