30 #include <boost/filesystem/operations.hpp>
31 #include <boost/filesystem/path.hpp>
35 int main(
int argc,
char** argv)
37 ros::init(argc, argv,
"export_genicam_xml");
43 std::string guid = pnh.
param<std::string>(
"guid",
"");
46 std::string xmlFileStr = pnh.
param<std::string>(
"xml_file",
"");
50 arv_update_device_list();
51 uint n_interfaces = arv_get_n_interfaces();
52 ROS_INFO(
"# Interfaces: %d", n_interfaces);
54 uint n_devices = arv_get_n_devices();
55 ROS_INFO(
"# Devices: %d", n_devices);
56 for (uint i = 0; i < n_devices; i++)
57 ROS_INFO(
"Device%d: %s", i, arv_get_device_id(i));
66 ArvCamera *p_camera =
nullptr;
72 p_camera = arv_camera_new(NULL);
76 ROS_INFO(
"Opening: %s", guid.c_str());
77 p_camera = arv_camera_new(guid.c_str());
83 ArvDevice *p_device = arv_camera_get_device(p_camera);
84 const char* vendor_name = arv_camera_get_vendor_name(p_camera);
85 const char* model_name = arv_camera_get_model_name(p_camera);
86 const char* device_id = arv_camera_get_device_id(p_camera);
87 const char* device_sn = arv_device_get_string_feature_value(p_device,
"DeviceSerialNumber");
88 ROS_INFO(
"Successfully Opened: %s-%s-%s", vendor_name, model_name,
89 (device_sn) ? device_sn : device_id);
94 boost::filesystem::path xmlFilePath;
95 if(xmlFileStr.empty())
97 std::string tmpFileName =
"";
100 tmpFileName += std::string(vendor_name);
101 tmpFileName +=
"-" + std::string(model_name);
102 tmpFileName +=
"-" + std::string((device_sn) ? device_sn : device_id);
109 xmlFilePath = boost::filesystem::path(tmpFileName +
".xml");
113 xmlFilePath = boost::filesystem::path(xmlFileStr);
117 xmlFilePath = boost::filesystem::absolute(xmlFilePath);
120 if(boost::filesystem::exists(xmlFilePath))
121 ROS_WARN(
"Output file already exists and will be overwritten. Path: %s",
122 boost::filesystem::canonical(xmlFilePath).c_str());
125 if(!xmlFilePath.parent_path().empty())
126 boost::filesystem::create_directories(xmlFilePath.parent_path());
130 const char* p_xmldata = arv_device_get_genicam_xml(p_device, &xmlSize);
132 fout.open(xmlFilePath.c_str(), std::ios::binary | std::ios::out);
133 fout.write(p_xmldata, xmlSize);
136 ROS_INFO(
"Written GenICam XML to file: %s", boost::filesystem::canonical(xmlFilePath).c_str());
139 g_object_unref(p_camera);