export_genicam_xml_node.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * camera_aravis
4  *
5  * Copyright © 2024 Fraunhofer IOSB and contributors
6  *
7  * This library is free software; you can redistribute it and/or
8  * modify it under the terms of the GNU Library General Public
9  * License as published by the Free Software Foundation; either
10  * version 2 of the License, or (at your option) any later version.
11  *
12  * This library is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
15  * Library General Public License for more details.
16  *
17  * You should have received a copy of the GNU Library General Public
18  * License along with this library; if not, write to the
19  * Free Software Foundation, Inc., 51 Franklin St, Fifth Floor,
20  * Boston, MA 02110-1301, USA.
21  *
22  ****************************************************************************/
23 
24 extern "C" {
25 #include <arv.h>
26 }
27 
28 #include <fstream>
29 
30 #include <boost/filesystem/operations.hpp>
31 #include <boost/filesystem/path.hpp>
32 
33 #include <ros/ros.h>
34 
35 int main(int argc, char** argv)
36 {
37  ros::init(argc, argv, "export_genicam_xml");
38 
40  ros::NodeHandle pnh("~");
41 
43  std::string guid = pnh.param<std::string>("guid", "");
44 
46  std::string xmlFileStr = pnh.param<std::string>("xml_file", "");
47 
48  //--- Print out some useful info.
49  ROS_INFO("Attached cameras:");
50  arv_update_device_list();
51  uint n_interfaces = arv_get_n_interfaces();
52  ROS_INFO("# Interfaces: %d", n_interfaces);
53 
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));
58 
59  if (n_devices == 0)
60  {
61  ROS_ERROR("No cameras detected.");
62  return -1;
63  }
64 
65  //--- Open the camera.
66  ArvCamera *p_camera = nullptr;
67  while (!p_camera)
68  {
69  if (guid.empty())
70  {
71  ROS_INFO("Opening: (any)");
72  p_camera = arv_camera_new(NULL);
73  }
74  else
75  {
76  ROS_INFO("Opening: %s", guid.c_str());
77  p_camera = arv_camera_new(guid.c_str());
78  }
79  ros::Duration(1.0).sleep();
80  }
81 
82  //--- get device
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);
90 
91  //--- if xmlFileStr is empty construct relative path from guid
92 
94  boost::filesystem::path xmlFilePath;
95  if(xmlFileStr.empty())
96  {
97  std::string tmpFileName = "";
98  if(guid.empty())
99  {
100  tmpFileName += std::string(vendor_name);
101  tmpFileName += "-" + std::string(model_name);
102  tmpFileName += "-" + std::string((device_sn) ? device_sn : device_id);
103  }
104  else
105  {
106  tmpFileName = guid;
107  }
108 
109  xmlFilePath = boost::filesystem::path(tmpFileName + ".xml");
110  }
111  else
112  {
113  xmlFilePath = boost::filesystem::path(xmlFileStr);
114  }
115 
116  //--- make path absolute
117  xmlFilePath = boost::filesystem::absolute(xmlFilePath);
118 
119  //--- print warning if file already exists
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());
123 
124  //--- make parent directory if not existing
125  if(!xmlFilePath.parent_path().empty())
126  boost::filesystem::create_directories(xmlFilePath.parent_path());
127 
128  //--- extract and save XML
129  size_t xmlSize = 0;
130  const char* p_xmldata = arv_device_get_genicam_xml(p_device, &xmlSize);
131  std::ofstream fout;
132  fout.open(xmlFilePath.c_str(), std::ios::binary | std::ios::out);
133  fout.write(p_xmldata, xmlSize);
134  fout.close();
135 
136  ROS_INFO("Written GenICam XML to file: %s", boost::filesystem::canonical(xmlFilePath).c_str());
137 
138  //--- release camera
139  g_object_unref(p_camera);
140 
141  return 0;
142 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ROS_WARN
#define ROS_WARN(...)
main
int main(int argc, char **argv)
Definition: export_genicam_xml_node.cpp:35
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::Duration::sleep
bool sleep() const
ROS_INFO
#define ROS_INFO(...)
ros::Duration
ros::NodeHandle


camera_aravis
Author(s): Boitumelo Ruf, Fraunhofer IOSB , Dominik Kleiser, Fraunhofer IOSB , Dominik A. Klein, Fraunhofer FKIE , Steve Safarik, Straw Lab , Andrew Straw, Straw Lab , Floris van Breugel, van Breugel Lab
autogenerated on Wed Sep 25 2024 02:23:21