camera_aravis_nodelet.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * camera_aravis
4  *
5  * Copyright © 2022 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 #ifndef CAMERA_ARAVIS_CAMERA_ARAVIS_NODELET
25 #define CAMERA_ARAVIS_CAMERA_ARAVIS_NODELET
26 
27 extern "C" {
28 #include <arv.h>
29 }
30 
31 #include <iostream>
32 #include <stdlib.h>
33 #include <math.h>
34 #include <string.h>
35 #include <algorithm>
36 #include <functional>
37 #include <cctype>
38 #include <memory>
39 #include <atomic>
40 #include <thread>
41 #include <chrono>
42 #include <unordered_map>
43 
44 #include <glib.h>
45 
46 #include <ros/ros.h>
47 #include <nodelet/nodelet.h>
48 #include <nodelet/NodeletUnload.h>
49 #include <ros/time.h>
50 #include <ros/duration.h>
51 #include <sensor_msgs/Image.h>
52 #include <std_msgs/Int64.h>
55 #include <boost/algorithm/string/trim.hpp>
56 
57 #include <dynamic_reconfigure/server.h>
58 #include <dynamic_reconfigure/SensorLevels.h>
59 #include <tf/transform_listener.h>
62 #include <camera_aravis/CameraAravisConfig.h>
63 #include <camera_aravis/CameraAutoInfo.h>
64 #include <camera_aravis/ExtendedCameraInfo.h>
65 
66 #include <camera_aravis/get_integer_feature_value.h>
67 #include <camera_aravis/set_integer_feature_value.h>
68 #include <camera_aravis/get_float_feature_value.h>
69 #include <camera_aravis/set_float_feature_value.h>
70 #include <camera_aravis/get_string_feature_value.h>
71 #include <camera_aravis/set_string_feature_value.h>
72 #include <camera_aravis/get_boolean_feature_value.h>
73 #include <camera_aravis/set_boolean_feature_value.h>
74 
77 
78 namespace camera_aravis
79 {
80 
81 typedef CameraAravisConfig Config;
82 
84 {
85 public:
87  virtual ~CameraAravisNodelet();
88 
89 private:
90  bool verbose_ = false;
91  std::string guid_ = "";
92  bool use_ptp_stamp_ = false;
93  bool pub_ext_camera_info_ = false;
94  bool pub_tf_optical_ = false;
95 
96  ArvCamera *p_camera_ = NULL;
97  ArvDevice *p_device_ = NULL;
98 
99  gint num_streams_ = 0;
100  std::vector<ArvStream *> p_streams_;
101  std::vector<std::string> stream_names_;
102  std::vector<CameraBufferPool::Ptr> p_buffer_pools_;
103  int32_t acquire_ = 0;
104  std::vector<ConversionFunction> convert_formats;
105 
106  virtual void onInit() override;
107  void spawnStream();
108 
109 
110 protected:
111  // reset PTP clock
113 
114  // apply auto functions from a ros message
115  void cameraAutoInfoCallback(const CameraAutoInfoConstPtr &msg_ptr);
116 
118  void setAutoMaster(bool value);
119  void setAutoSlave(bool value);
120 
121  void setExtendedCameraInfo(std::string channel_name, size_t stream_id);
122  void fillExtendedCameraInfoMessage(ExtendedCameraInfo &msg);
123 
124  // Extra stream options for GigEVision streams.
125  void tuneGvStream(ArvGvStream *p_stream);
126 
127  void rosReconfigureCallback(Config &config, uint32_t level);
128 
129  // Start and stop camera on demand
130  void rosConnectCallback();
131 
132  // Callback to wrap and send recorded image as ROS message
133  static void newBufferReadyCallback(ArvStream *p_stream, gpointer can_instance);
134 
135  // Buffer Callback Helper
136  static void newBufferReady(ArvStream *p_stream, CameraAravisNodelet *p_can, std::string frame_id, size_t stream_id);
137 
138  // Clean-up if aravis device is lost
139  static void controlLostCallback(ArvDevice *p_gv_device, gpointer can_instance);
140 
141  // Services
143  bool getIntegerFeatureCallback(camera_aravis::get_integer_feature_value::Request& request, camera_aravis::get_integer_feature_value::Response& response);
144 
146  bool getFloatFeatureCallback(camera_aravis::get_float_feature_value::Request& request, camera_aravis::get_float_feature_value::Response& response);
147 
149  bool getStringFeatureCallback(camera_aravis::get_string_feature_value::Request& request, camera_aravis::get_string_feature_value::Response& response);
150 
152  bool getBooleanFeatureCallback(camera_aravis::get_boolean_feature_value::Request& request, camera_aravis::get_boolean_feature_value::Response& response);
153 
155  bool setIntegerFeatureCallback(camera_aravis::set_integer_feature_value::Request& request, camera_aravis::set_integer_feature_value::Response& response);
156 
158  bool setFloatFeatureCallback(camera_aravis::set_float_feature_value::Request& request, camera_aravis::set_float_feature_value::Response& response);
159 
161  bool setStringFeatureCallback(camera_aravis::set_string_feature_value::Request& request, camera_aravis::set_string_feature_value::Response& response);
162 
164  bool setBooleanFeatureCallback(camera_aravis::set_boolean_feature_value::Request& request, camera_aravis::set_boolean_feature_value::Response& response);
165 
166  // triggers a shot at regular intervals, sleeps in between
167  void softwareTriggerLoop();
168 
169  void publishTfLoop(double rate);
170 
171  void discoverFeatures();
172 
173  static void parseStringArgs(std::string in_arg_string, std::vector<std::string> &out_args);
174 
175  // WriteCameraFeaturesFromRosparam()
176  // Read ROS parameters from this node's namespace, and see if each parameter has a similarly named & typed feature in the camera. Then set the
177  // camera feature to that value. For example, if the parameter camnode/Gain is set to 123.0, then we'll write 123.0 to the Gain feature
178  // in the camera.
179  //
180  // Note that the datatype of the parameter *must* match the datatype of the camera feature, and this can be determined by
181  // looking at the camera's XML file. Camera enum's are string parameters, camera bools are false/true parameters (not 0/1),
182  // integers are integers, doubles are doubles, etc.
184 
185  std::unique_ptr<dynamic_reconfigure::Server<Config> > reconfigure_server_;
186  boost::recursive_mutex reconfigure_mutex_;
187 
188  std::vector<image_transport::CameraPublisher> cam_pubs_;
189  std::vector<std::unique_ptr<camera_info_manager::CameraInfoManager>> p_camera_info_managers_;
190  std::vector<std::unique_ptr<ros::NodeHandle>> p_camera_info_node_handles_;
191  std::vector<sensor_msgs::CameraInfoPtr> camera_infos_;
192 
193  std::unique_ptr<tf2_ros::StaticTransformBroadcaster> p_stb_;
194  std::unique_ptr<tf2_ros::TransformBroadcaster> p_tb_;
195  geometry_msgs::TransformStamped tf_optical_;
196  std::thread tf_dyn_thread_;
197  std::atomic_bool tf_thread_active_;
198 
199  CameraAutoInfo auto_params_;
202 
203  boost::recursive_mutex extended_camera_info_mutex_;
204  std::vector<ros::Publisher> extended_camera_info_pubs_;
205 
209 
210  std::atomic<bool> spawning_;
211  std::thread spawn_stream_thread_;
212 
213  std::thread software_trigger_thread_;
214  std::atomic_bool software_trigger_active_;
215  size_t n_buffers_ = 0;
216 
217  std::unordered_map<std::string, const bool> implemented_features_;
218 
219  struct
220  {
221  int32_t x = 0;
222  int32_t y = 0;
223  int32_t width = 0;
224  int32_t width_min = 0;
225  int32_t width_max = 0;
226  int32_t height = 0;
227  int32_t height_min = 0;
228  int32_t height_max = 0;
229  } roi_;
230 
231  struct Sensor
232  {
233  int32_t width = 0;
234  int32_t height = 0;
235  std::string pixel_format;
236  size_t n_bits_pixel = 0;
237  };
238 
239  std::vector<Sensor *> sensors_;
240 
241  struct StreamIdData
242  {
244  size_t stream_id;
245  };
246 };
247 
248 } // end namespace camera_aravis
249 
250 #endif /* CAMERA_ARAVIS_CAMERA_ARAVIS_NODELET */
camera_aravis::CameraAravisNodelet::tf_thread_active_
std::atomic_bool tf_thread_active_
Definition: camera_aravis_nodelet.h:218
camera_aravis::CameraAravisNodelet::auto_sub_
ros::Subscriber auto_sub_
Definition: camera_aravis_nodelet.h:222
camera_aravis::CameraAravisNodelet::setStringFeatureCallback
bool setStringFeatureCallback(camera_aravis::set_string_feature_value::Request &request, camera_aravis::set_string_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:601
camera_aravis::CameraAravisNodelet::tf_dyn_thread_
std::thread tf_dyn_thread_
Definition: camera_aravis_nodelet.h:217
camera_aravis::CameraAravisNodelet::rosConnectCallback
void rosConnectCallback()
Definition: camera_aravis_nodelet.cpp:1158
camera_aravis::CameraAravisNodelet::x
int32_t x
Definition: camera_aravis_nodelet.h:242
camera_aravis::CameraAravisNodelet::newBufferReady
static void newBufferReady(ArvStream *p_stream, CameraAravisNodelet *p_can, std::string frame_id, size_t stream_id)
Definition: camera_aravis_nodelet.cpp:1193
camera_aravis::CameraAravisNodelet::width
int32_t width
Definition: camera_aravis_nodelet.h:244
ros::Publisher
camera_aravis::CameraAravisNodelet::fillExtendedCameraInfoMessage
void fillExtendedCameraInfoMessage(ExtendedCameraInfo &msg)
Definition: camera_aravis_nodelet.cpp:1289
camera_aravis::CameraAravisNodelet::Sensor::width
int32_t width
Definition: camera_aravis_nodelet.h:254
camera_aravis::CameraAravisNodelet::setExtendedCameraInfo
void setExtendedCameraInfo(std::string channel_name, size_t stream_id)
Definition: camera_aravis_nodelet.cpp:877
camera_aravis::CameraAravisNodelet::p_tb_
std::unique_ptr< tf2_ros::TransformBroadcaster > p_tb_
Definition: camera_aravis_nodelet.h:215
camera_aravis::CameraAravisNodelet::get_integer_service_
ros::ServiceServer get_integer_service_
Definition: camera_aravis_nodelet.h:163
camera_aravis::CameraAravisNodelet::tf_optical_
geometry_msgs::TransformStamped tf_optical_
Definition: camera_aravis_nodelet.h:216
camera_aravis::CameraAravisNodelet::StreamIdData::can
CameraAravisNodelet * can
Definition: camera_aravis_nodelet.h:264
camera_aravis::CameraAravisNodelet::config_min_
Config config_min_
Definition: camera_aravis_nodelet.h:228
camera_aravis::CameraAravisNodelet::set_integer_service_
ros::ServiceServer set_integer_service_
Definition: camera_aravis_nodelet.h:175
camera_buffer_pool.h
camera_aravis::CameraAravisNodelet::height_min
int32_t height_min
Definition: camera_aravis_nodelet.h:248
ros.h
camera_aravis::CameraAravisNodelet::~CameraAravisNodelet
virtual ~CameraAravisNodelet()
Definition: camera_aravis_nodelet.cpp:57
time.h
camera_info_manager.h
camera_aravis::CameraAravisNodelet::extended_camera_info_pubs_
std::vector< ros::Publisher > extended_camera_info_pubs_
Definition: camera_aravis_nodelet.h:225
camera_aravis::CameraAravisNodelet::software_trigger_thread_
std::thread software_trigger_thread_
Definition: camera_aravis_nodelet.h:234
camera_aravis::CameraAravisNodelet::StreamIdData::stream_id
size_t stream_id
Definition: camera_aravis_nodelet.h:265
camera_aravis::CameraAravisNodelet::convert_formats
std::vector< ConversionFunction > convert_formats
Definition: camera_aravis_nodelet.h:125
camera_aravis::CameraAravisNodelet::syncAutoParameters
void syncAutoParameters()
Definition: camera_aravis_nodelet.cpp:755
camera_aravis::Config
CameraAravisConfig Config
Definition: camera_aravis_nodelet.h:102
camera_aravis
Definition: camera_aravis_nodelet.h:78
camera_aravis::CameraAravisNodelet::get_boolean_service_
ros::ServiceServer get_boolean_service_
Definition: camera_aravis_nodelet.h:172
camera_aravis::CameraAravisNodelet::guid_
std::string guid_
Definition: camera_aravis_nodelet.h:112
camera_aravis::CameraAravisNodelet::p_streams_
std::vector< ArvStream * > p_streams_
Definition: camera_aravis_nodelet.h:121
camera_aravis::CameraAravisNodelet::acquire_
int32_t acquire_
Definition: camera_aravis_nodelet.h:124
camera_aravis::CameraAravisNodelet::pub_tf_optical_
bool pub_tf_optical_
Definition: camera_aravis_nodelet.h:115
camera_aravis::CameraAravisNodelet::getIntegerFeatureCallback
bool getIntegerFeatureCallback(camera_aravis::get_integer_feature_value::Request &request, camera_aravis::get_integer_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:554
camera_aravis::CameraAravisNodelet::p_camera_
ArvCamera * p_camera_
Definition: camera_aravis_nodelet.h:117
camera_aravis::CameraAravisNodelet::CameraAravisNodelet
CameraAravisNodelet()
Definition: camera_aravis_nodelet.cpp:53
camera_aravis::CameraAravisNodelet::spawnStream
void spawnStream()
Definition: camera_aravis_nodelet.cpp:466
camera_aravis::CameraAravisNodelet
Definition: camera_aravis_nodelet.h:104
transform_broadcaster.h
camera_aravis::CameraAravisNodelet::getStringFeatureCallback
bool getStringFeatureCallback(camera_aravis::get_string_feature_value::Request &request, camera_aravis::get_string_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:594
camera_aravis::CameraAravisNodelet::getBooleanFeatureCallback
bool getBooleanFeatureCallback(camera_aravis::get_boolean_feature_value::Request &request, camera_aravis::get_boolean_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:614
ros::ServiceServer
camera_aravis::CameraAravisNodelet::publishTfLoop
void publishTfLoop(double rate)
Definition: camera_aravis_nodelet.cpp:1405
camera_aravis::CameraAravisNodelet::sensors_
std::vector< Sensor * > sensors_
Definition: camera_aravis_nodelet.h:260
camera_aravis::CameraAravisNodelet::camera_infos_
std::vector< sensor_msgs::CameraInfoPtr > camera_infos_
Definition: camera_aravis_nodelet.h:212
camera_aravis::CameraAravisNodelet::get_string_service_
ros::ServiceServer get_string_service_
Definition: camera_aravis_nodelet.h:169
duration.h
camera_aravis::CameraAravisNodelet::config_max_
Config config_max_
Definition: camera_aravis_nodelet.h:229
camera_aravis::CameraAravisNodelet::p_device_
ArvDevice * p_device_
Definition: camera_aravis_nodelet.h:118
camera_aravis::CameraAravisNodelet::spawn_stream_thread_
std::thread spawn_stream_thread_
Definition: camera_aravis_nodelet.h:232
camera_aravis::CameraAravisNodelet::height_max
int32_t height_max
Definition: camera_aravis_nodelet.h:249
camera_aravis::CameraAravisNodelet::config_
Config config_
Definition: camera_aravis_nodelet.h:227
camera_aravis::CameraAravisNodelet::p_camera_info_node_handles_
std::vector< std::unique_ptr< ros::NodeHandle > > p_camera_info_node_handles_
Definition: camera_aravis_nodelet.h:211
camera_aravis::CameraAravisNodelet::setIntegerFeatureCallback
bool setIntegerFeatureCallback(camera_aravis::set_integer_feature_value::Request &request, camera_aravis::set_integer_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:561
camera_aravis::CameraAravisNodelet::reconfigure_server_
std::unique_ptr< dynamic_reconfigure::Server< Config > > reconfigure_server_
Definition: camera_aravis_nodelet.h:206
camera_aravis::CameraAravisNodelet::tuneGvStream
void tuneGvStream(ArvGvStream *p_stream)
Definition: camera_aravis_nodelet.cpp:894
camera_aravis::CameraAravisNodelet::n_buffers_
size_t n_buffers_
Definition: camera_aravis_nodelet.h:236
camera_aravis::CameraAravisNodelet::set_boolean_service_
ros::ServiceServer set_boolean_service_
Definition: camera_aravis_nodelet.h:184
camera_aravis::CameraAravisNodelet::extended_camera_info_mutex_
boost::recursive_mutex extended_camera_info_mutex_
Definition: camera_aravis_nodelet.h:224
camera_aravis::CameraAravisNodelet::writeCameraFeaturesFromRosparam
void writeCameraFeaturesFromRosparam()
Definition: camera_aravis_nodelet.cpp:1518
camera_aravis::CameraAravisNodelet::newBufferReadyCallback
static void newBufferReadyCallback(ArvStream *p_stream, gpointer can_instance)
Definition: camera_aravis_nodelet.cpp:1174
camera_aravis::CameraAravisNodelet::stream_names_
std::vector< std::string > stream_names_
Definition: camera_aravis_nodelet.h:122
camera_aravis::CameraAravisNodelet::p_camera_info_managers_
std::vector< std::unique_ptr< camera_info_manager::CameraInfoManager > > p_camera_info_managers_
Definition: camera_aravis_nodelet.h:210
conversion_utils.h
camera_aravis::CameraAravisNodelet::set_float_service_
ros::ServiceServer set_float_service_
Definition: camera_aravis_nodelet.h:178
camera_aravis::CameraAravisNodelet::width_max
int32_t width_max
Definition: camera_aravis_nodelet.h:246
camera_aravis::CameraAravisNodelet::discoverFeatures
void discoverFeatures()
Definition: camera_aravis_nodelet.cpp:1425
camera_aravis::CameraAravisNodelet::set_string_service_
ros::ServiceServer set_string_service_
Definition: camera_aravis_nodelet.h:181
camera_aravis::CameraAravisNodelet::spawning_
std::atomic< bool > spawning_
Definition: camera_aravis_nodelet.h:231
camera_aravis::CameraAravisNodelet::cam_pubs_
std::vector< image_transport::CameraPublisher > cam_pubs_
Definition: camera_aravis_nodelet.h:209
camera_aravis::CameraAravisNodelet::roi_
struct camera_aravis::CameraAravisNodelet::@0 roi_
camera_aravis::CameraAravisNodelet::setBooleanFeatureCallback
bool setBooleanFeatureCallback(camera_aravis::set_boolean_feature_value::Request &request, camera_aravis::set_boolean_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:621
image_transport.h
camera_aravis::CameraAravisNodelet::auto_params_
CameraAutoInfo auto_params_
Definition: camera_aravis_nodelet.h:220
transform_listener.h
camera_aravis::CameraAravisNodelet::Sensor::height
int32_t height
Definition: camera_aravis_nodelet.h:255
camera_aravis::CameraAravisNodelet::rosReconfigureCallback
void rosReconfigureCallback(Config &config, uint32_t level)
Definition: camera_aravis_nodelet.cpp:921
camera_aravis::CameraAravisNodelet::pub_ext_camera_info_
bool pub_ext_camera_info_
Definition: camera_aravis_nodelet.h:114
camera_aravis::CameraAravisNodelet::verbose_
bool verbose_
Definition: camera_aravis_nodelet.h:111
camera_aravis::CameraAravisNodelet::StreamIdData
Definition: camera_aravis_nodelet.h:262
camera_aravis::CameraAravisNodelet::parseStringArgs
static void parseStringArgs(std::string in_arg_string, std::vector< std::string > &out_args)
Definition: camera_aravis_nodelet.cpp:1490
nodelet::Nodelet
camera_aravis::CameraAravisNodelet::auto_pub_
ros::Publisher auto_pub_
Definition: camera_aravis_nodelet.h:221
camera_aravis::CameraAravisNodelet::onInit
virtual void onInit() override
Definition: camera_aravis_nodelet.cpp:114
camera_aravis::CameraAravisNodelet::reconfigure_mutex_
boost::recursive_mutex reconfigure_mutex_
Definition: camera_aravis_nodelet.h:207
nodelet.h
camera_aravis::CameraAravisNodelet::y
int32_t y
Definition: camera_aravis_nodelet.h:243
camera_aravis::CameraAravisNodelet::width_min
int32_t width_min
Definition: camera_aravis_nodelet.h:245
camera_aravis::CameraAravisNodelet::setFloatFeatureCallback
bool setFloatFeatureCallback(camera_aravis::set_float_feature_value::Request &request, camera_aravis::set_float_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:581
camera_aravis::CameraAravisNodelet::setAutoMaster
void setAutoMaster(bool value)
Definition: camera_aravis_nodelet.cpp:825
camera_aravis::CameraAravisNodelet::num_streams_
gint num_streams_
Definition: camera_aravis_nodelet.h:120
camera_aravis::CameraAravisNodelet::softwareTriggerLoop
void softwareTriggerLoop()
Definition: camera_aravis_nodelet.cpp:1378
camera_aravis::CameraAravisNodelet::controlLostCallback
static void controlLostCallback(ArvDevice *p_gv_device, gpointer can_instance)
Definition: camera_aravis_nodelet.cpp:1366
camera_aravis::CameraAravisNodelet::get_float_service_
ros::ServiceServer get_float_service_
Definition: camera_aravis_nodelet.h:166
static_transform_broadcaster.h
camera_aravis::CameraAravisNodelet::software_trigger_active_
std::atomic_bool software_trigger_active_
Definition: camera_aravis_nodelet.h:235
camera_aravis::CameraAravisNodelet::Sensor
Definition: camera_aravis_nodelet.h:252
camera_aravis::CameraAravisNodelet::getFloatFeatureCallback
bool getFloatFeatureCallback(camera_aravis::get_float_feature_value::Request &request, camera_aravis::get_float_feature_value::Response &response)
Definition: camera_aravis_nodelet.cpp:574
camera_aravis::CameraAravisNodelet::p_stb_
std::unique_ptr< tf2_ros::StaticTransformBroadcaster > p_stb_
Definition: camera_aravis_nodelet.h:214
camera_aravis::CameraAravisNodelet::p_buffer_pools_
std::vector< CameraBufferPool::Ptr > p_buffer_pools_
Definition: camera_aravis_nodelet.h:123
camera_aravis::CameraAravisNodelet::implemented_features_
std::unordered_map< std::string, const bool > implemented_features_
Definition: camera_aravis_nodelet.h:238
camera_aravis::CameraAravisNodelet::resetPtpClock
void resetPtpClock()
Definition: camera_aravis_nodelet.cpp:634
camera_aravis::CameraAravisNodelet::Sensor::n_bits_pixel
size_t n_bits_pixel
Definition: camera_aravis_nodelet.h:257
camera_aravis::CameraAravisNodelet::setAutoSlave
void setAutoSlave(bool value)
Definition: camera_aravis_nodelet.cpp:838
camera_aravis::CameraAravisNodelet::height
int32_t height
Definition: camera_aravis_nodelet.h:247
camera_aravis::CameraAravisNodelet::Sensor::pixel_format
std::string pixel_format
Definition: camera_aravis_nodelet.h:256
camera_aravis::CameraAravisNodelet::use_ptp_stamp_
bool use_ptp_stamp_
Definition: camera_aravis_nodelet.h:113
ros::Subscriber
camera_aravis::CameraAravisNodelet::cameraAutoInfoCallback
void cameraAutoInfoCallback(const CameraAutoInfoConstPtr &msg_ptr)
Definition: camera_aravis_nodelet.cpp:647


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 Sun Dec 25 2022 03:22:59