ueye_cam_nodelet.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * DO NOT MODIFY - AUTO-GENERATED
3 *
4 *
5 * DISCLAMER:
6 *
7 * This project was created within an academic research setting, and thus should
8 * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
9 * code, so please adjust expectations accordingly. With that said, we are
10 * intrinsically motivated to ensure its correctness (and often its performance).
11 * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
12 * to file bugs, suggestions, pull requests; we will do our best to address them
13 * in a timely manner.
14 *
15 *
16 * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
17 *
18 * Copyright (c) 2013-2016, Anqi Xu and contributors
19 * All rights reserved.
20 *
21 * Redistribution and use in source and binary forms, with or without
22 * modification, are permitted provided that the following conditions
23 * are met:
24 *
25 * * Redistributions of source code must retain the above copyright
26 * notice, this list of conditions and the following disclaimer.
27 * * Redistributions in binary form must reproduce the above
28 * copyright notice, this list of conditions and the following
29 * disclaimer in the documentation and/or other materials provided
30 * with the distribution.
31 * * Neither the name of the School of Computer Science, McGill University,
32 * nor the names of its contributors may be used to endorse or promote
33 * products derived from this software without specific prior written
34 * permission.
35 *
36 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
37 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
38 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
39 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
40 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
41 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
42 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
43 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
44 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
45 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
46 *******************************************************************************/
47 
49 #include <cstdlib> // needed for getenv()
50 #include <ros/package.h>
52 #include <std_msgs/UInt64.h>
53 #include <sensor_msgs/fill_image.h>
55 
56 
57 //#define DEBUG_PRINTOUT_FRAME_GRAB_RATES
58 
59 
60 using namespace std;
61 using namespace sensor_msgs::image_encodings;
62 
63 
64 namespace ueye_cam {
65 
66 
67 const std::string UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera";
68 const std::string UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera";
69 const std::string UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw";
70 const std::string UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC = "timeout_count";
71 const std::string UEyeCamNodelet::DEFAULT_COLOR_MODE = "";
72 constexpr int UEyeCamDriver::ANY_CAMERA; // Needed since CMakeLists.txt creates 2 separate libraries: one for non-ROS parent class, and one for ROS child class
73 
74 
75 // Note that these default settings will be overwritten by queryCamParams() during connectCam()
76 UEyeCamNodelet::UEyeCamNodelet():
77  nodelet::Nodelet(),
78  UEyeCamDriver(ANY_CAMERA, DEFAULT_CAMERA_NAME),
79  frame_grab_alive_(false),
80  ros_cfg_(nullptr),
81  cfg_sync_requested_(false),
82  ros_frame_count_(0),
83  timeout_count_(0),
84  cam_topic_(DEFAULT_CAMERA_TOPIC),
85  timeout_topic_(DEFAULT_TIMEOUT_TOPIC),
86  cam_intr_filename_(""),
87  cam_params_filename_(""),
88  init_clock_tick_(0),
89  init_publish_time_(0),
90  prev_output_frame_idx_(0) {
91  ros_image_.is_bigendian = (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__); // TODO: what about MS Windows?
92  cam_params_.image_width = DEFAULT_IMAGE_WIDTH;
93  cam_params_.image_height = DEFAULT_IMAGE_HEIGHT;
94  cam_params_.image_left = -1;
95  cam_params_.image_top = -1;
96  cam_params_.color_mode = DEFAULT_COLOR_MODE;
97  cam_params_.subsampling = static_cast<int>(cam_subsampling_rate_);
98  cam_params_.binning = static_cast<int>(cam_binning_rate_);
99  cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
100  cam_params_.auto_gain = false;
101  cam_params_.master_gain = 0;
102  cam_params_.red_gain = 0;
103  cam_params_.green_gain = 0;
104  cam_params_.blue_gain = 0;
105  cam_params_.gain_boost = 0;
106  cam_params_.software_gamma=100;
107  cam_params_.auto_exposure = false;
108  cam_params_.auto_exposure_reference = 128;
109  cam_params_.exposure = DEFAULT_EXPOSURE;
110  cam_params_.auto_white_balance = false;
111  cam_params_.white_balance_red_offset = 0;
112  cam_params_.white_balance_blue_offset = 0;
113  cam_params_.auto_frame_rate = false;
114  cam_params_.frame_rate = DEFAULT_FRAME_RATE;
115  cam_params_.output_rate = 0; // disable by default
116  cam_params_.pixel_clock = DEFAULT_PIXEL_CLOCK;
117  cam_params_.ext_trigger_mode = false;
118  cam_params_.flash_delay = 0;
119  cam_params_.flash_duration = DEFAULT_FLASH_DURATION;
120  cam_params_.gpio1 = 0;
121  cam_params_.gpio2 = 0;
122  cam_params_.pwm_freq = 1;
123  cam_params_.pwm_duty_cycle=0.5;
124  cam_params_.flip_upd = false;
125  cam_params_.flip_lr = false;
126 }
127 
128 
130  disconnectCam();
131 
132  // NOTE: sometimes deleting dynamic reconfigure object will lock up
133  // (suspect the scoped lock is not releasing the recursive mutex)
134  //
135  //if (ros_cfg_ != NULL) {
136  // delete ros_cfg_;
137  // ros_cfg_ = NULL;
138  //}
139 }
140 
141 
146 
147  // Load camera-agnostic ROS parameters
148  local_nh.param<string>("camera_name", cam_name_, DEFAULT_CAMERA_NAME);
149  local_nh.param<string>("frame_name", frame_name_, DEFAULT_FRAME_NAME);
150  local_nh.param<string>("camera_topic", cam_topic_, DEFAULT_CAMERA_TOPIC);
151  local_nh.param<string>("timeout_topic", timeout_topic_, DEFAULT_TIMEOUT_TOPIC);
152  local_nh.param<string>("camera_intrinsics_file", cam_intr_filename_, "");
153  local_nh.param<int>("camera_id", cam_id_, ANY_CAMERA);
154  local_nh.param<string>("camera_parameters_file", cam_params_filename_, "");
155  if (cam_id_ < 0) {
156  WARN_STREAM("Invalid camera ID specified: " << cam_id_ <<
157  "; setting to ANY_CAMERA");
158  cam_id_ = ANY_CAMERA;
159  }
160 
162 
163  // Setup publishers, subscribers, and services
164  ros_cam_pub_ = it.advertiseCamera(cam_name_ + "/" + cam_topic_, 1);
165  set_cam_info_srv_ = nh.advertiseService(cam_name_ + "/set_camera_info",
167  timeout_pub_ = nh.advertise<std_msgs::UInt64>(cam_name_ + "/" + timeout_topic_, 1, true);
168  std_msgs::UInt64 timeout_msg; timeout_msg.data = 0; timeout_pub_.publish(timeout_msg);
169 
170  // Initiate camera and start capture
171  if (connectCam() != IS_SUCCESS) {
172  ERROR_STREAM("Failed to initialize [" << cam_name_ << "]");
173  return;
174  }
175 
176  // Setup dynamic reconfigure server
177  ros_cfg_ = new ReconfigureServer(ros_cfg_mutex_, local_nh);
178  ReconfigureServer::CallbackType f;
179  f = bind(&UEyeCamNodelet::configCallback, this, _1, _2);
180  ros_cfg_->setCallback(f); // this will call configCallback, which will configure the camera's parameters
182  INFO_STREAM(
183  "UEye camera [" << cam_name_ << "] initialized on topic " << ros_cam_pub_.getTopic() << endl <<
184  "Width:\t\t\t" << cam_params_.image_width << endl <<
185  "Height:\t\t\t" << cam_params_.image_height << endl <<
186  "Left Pos.:\t\t" << cam_params_.image_left << endl <<
187  "Top Pos.:\t\t" << cam_params_.image_top << endl <<
188  "Color Mode:\t\t" << cam_params_.color_mode << endl <<
189  "Subsampling:\t\t" << cam_params_.subsampling << endl <<
190  "Binning:\t\t" << cam_params_.binning << endl <<
191  "Sensor Scaling:\t\t" << cam_params_.sensor_scaling << endl <<
192  "Auto Gain:\t\t" << cam_params_.auto_gain << endl <<
193  "Master Gain:\t\t" << cam_params_.master_gain << endl <<
194  "Red Gain:\t\t" << cam_params_.red_gain << endl <<
195  "Green Gain:\t\t" << cam_params_.green_gain << endl <<
196  "Blue Gain:\t\t" << cam_params_.blue_gain << endl <<
197  "Gain Boost:\t\t" << cam_params_.gain_boost << endl <<
198  "Software Gamma:\t\t" << cam_params_.software_gamma << endl <<
199  "Auto Exposure:\t\t" << cam_params_.auto_exposure << endl <<
200  "Auto Exposure Reference:\t" << cam_params_.auto_exposure_reference << endl <<
201  "Exposure (ms):\t\t" << cam_params_.exposure << endl <<
202  "Auto White Balance:\t" << cam_params_.auto_white_balance << endl <<
203  "WB Red Offset:\t\t" << cam_params_.white_balance_red_offset << endl <<
204  "WB Blue Offset:\t\t" << cam_params_.white_balance_blue_offset << endl <<
205  "Flash Delay (us):\t" << cam_params_.flash_delay << endl <<
206  "Flash Duration (us):\t" << cam_params_.flash_duration << endl <<
207  "Ext Trigger Mode:\t" << cam_params_.ext_trigger_mode << endl <<
208  "Auto Frame Rate:\t" << cam_params_.auto_frame_rate << endl <<
209  "Frame Rate (Hz):\t" << cam_params_.frame_rate << endl <<
210  "Output Rate (Hz):\t" << cam_params_.output_rate << endl <<
211  "Pixel Clock (MHz):\t" << cam_params_.pixel_clock << endl <<
212  "GPIO1 Mode:\t" << cam_params_.gpio1 << endl <<
213  "GPIO2 Mode:\t" << cam_params_.gpio1 << endl <<
214  "Mirror Image Upside Down:\t" << cam_params_.flip_upd << endl <<
215  "Mirror Image Left Right:\t" << cam_params_.flip_lr << endl
216  );
217 }
218 
219 
221  bool hasNewParams = false;
222  ueye_cam::UEyeCamConfig prevCamParams = cam_params_;
223  INT is_err = IS_SUCCESS;
224 
225  if (local_nh.hasParam("image_width")) {
226  local_nh.getParam("image_width", cam_params_.image_width);
227  if (cam_params_.image_width != prevCamParams.image_width) {
228  if (cam_params_.image_width <= 0) {
229  WARN_STREAM("Invalid requested image width for [" << cam_name_ <<
230  "]: " << cam_params_.image_width <<
231  "; using current width: " << prevCamParams.image_width);
232  cam_params_.image_width = prevCamParams.image_width;
233  } else {
234  hasNewParams = true;
235  }
236  }
237  } else {
238  local_nh.setParam("image_width", cam_params_.image_width);
239  }
240  if (local_nh.hasParam("image_height")) {
241  local_nh.getParam("image_height", cam_params_.image_height);
242  if (cam_params_.image_height != prevCamParams.image_height) {
243  if (cam_params_.image_height <= 0) {
244  WARN_STREAM("Invalid requested image height for [" << cam_name_ <<
245  "]: " << cam_params_.image_height <<
246  "; using current height: " << prevCamParams.image_height);
247  cam_params_.image_height = prevCamParams.image_height;
248  } else {
249  hasNewParams = true;
250  }
251  }
252  } else {
253  local_nh.setParam("image_height", cam_params_.image_height);
254  }
255  if (local_nh.hasParam("image_top")) {
256  local_nh.getParam("image_top", cam_params_.image_top);
257  if (cam_params_.image_top != prevCamParams.image_top) {
258  hasNewParams = true;
259  }
260  } else {
261  local_nh.setParam("image_top", cam_params_.image_top);
262  }
263  if (local_nh.hasParam("image_left")) {
264  local_nh.getParam("image_left", cam_params_.image_left);
265  if (cam_params_.image_left != prevCamParams.image_left) {
266  hasNewParams = true;
267  }
268  } else {
269  local_nh.setParam("image_left", cam_params_.image_left);
270  }
271  if (local_nh.hasParam("color_mode")) {
272  local_nh.getParam("color_mode", cam_params_.color_mode);
273  if (cam_params_.color_mode != prevCamParams.color_mode) {
274  if (cam_params_.color_mode.length() > 0) {
275  transform(cam_params_.color_mode.begin(),
276  cam_params_.color_mode.end(),
277  cam_params_.color_mode.begin(),
278  ::tolower);
279  if (name2colormode(cam_params_.color_mode) != 0) {
280  hasNewParams = true;
281  } else {
282  WARN_STREAM("Invalid requested color mode for [" << cam_name_
283  << "]: " << cam_params_.color_mode
284  << "; using current mode: " << prevCamParams.color_mode);
285  cam_params_.color_mode = prevCamParams.color_mode;
286  }
287  } else { // Empty requested color mode string
288  cam_params_.color_mode = prevCamParams.color_mode;
289  }
290  }
291  } else {
292  local_nh.setParam("color_mode", cam_params_.color_mode);
293  }
294  if (local_nh.hasParam("subsampling")) {
295  local_nh.getParam("subsampling", cam_params_.subsampling);
296  if (cam_params_.subsampling != prevCamParams.subsampling) {
297  if (!(cam_params_.subsampling == 1 ||
298  cam_params_.subsampling == 2 ||
299  cam_params_.subsampling == 4 ||
300  cam_params_.subsampling == 8 ||
301  cam_params_.subsampling == 16)) {
302  WARN_STREAM("Invalid or unsupported requested subsampling rate for [" <<
303  cam_name_ << "]: " << cam_params_.subsampling <<
304  "; using current rate: " << prevCamParams.subsampling);
305  cam_params_.subsampling = prevCamParams.subsampling;
306  } else {
307  hasNewParams = true;
308  }
309  }
310  } else {
311  local_nh.setParam("subsampling", cam_params_.subsampling);
312  }
313  if (local_nh.hasParam("auto_gain")) {
314  local_nh.getParam("auto_gain", cam_params_.auto_gain);
315  if (cam_params_.auto_gain != prevCamParams.auto_gain) {
316  hasNewParams = true;
317  }
318  } else {
319  local_nh.setParam("auto_gain", cam_params_.auto_gain);
320  }
321  if (local_nh.hasParam("master_gain")) {
322  local_nh.getParam("master_gain", cam_params_.master_gain);
323  if (cam_params_.master_gain != prevCamParams.master_gain) {
324  if (cam_params_.master_gain < 0 || cam_params_.master_gain > 100) {
325  WARN_STREAM("Invalid master gain for [" << cam_name_ << "]: " <<
326  cam_params_.master_gain << "; using current master gain: " << prevCamParams.master_gain);
327  cam_params_.master_gain = prevCamParams.master_gain;
328  } else {
329  hasNewParams = true;
330  }
331  }
332  } else {
333  local_nh.setParam("master_gain", cam_params_.master_gain);
334  }
335  if (local_nh.hasParam("red_gain")) {
336  local_nh.getParam("red_gain", cam_params_.red_gain);
337  if (cam_params_.red_gain != prevCamParams.red_gain) {
338  if (cam_params_.red_gain < 0 || cam_params_.red_gain > 100) {
339  WARN_STREAM("Invalid red gain for [" << cam_name_ << "]: " <<
340  cam_params_.red_gain << "; using current red gain: " << prevCamParams.red_gain);
341  cam_params_.red_gain = prevCamParams.red_gain;
342  } else {
343  hasNewParams = true;
344  }
345  }
346  } else {
347  local_nh.setParam("red_gain", cam_params_.red_gain);
348  }
349  if (local_nh.hasParam("green_gain")) {
350  local_nh.getParam("green_gain", cam_params_.green_gain);
351  if (cam_params_.green_gain != prevCamParams.green_gain) {
352  if (cam_params_.green_gain < 0 || cam_params_.green_gain > 100) {
353  WARN_STREAM("Invalid green gain for [" << cam_name_ << "]: " <<
354  cam_params_.green_gain << "; using current green gain: " << prevCamParams.green_gain);
355  cam_params_.green_gain = prevCamParams.green_gain;
356  } else {
357  hasNewParams = true;
358  }
359  }
360  } else {
361  local_nh.setParam("green_gain", cam_params_.green_gain);
362  }
363  if (local_nh.hasParam("blue_gain")) {
364  local_nh.getParam("blue_gain", cam_params_.blue_gain);
365  if (cam_params_.blue_gain != prevCamParams.blue_gain) {
366  if (cam_params_.blue_gain < 0 || cam_params_.blue_gain > 100) {
367  WARN_STREAM("Invalid blue gain for [" << cam_name_ << "]: " <<
368  cam_params_.blue_gain << "; using current blue gain: " << prevCamParams.blue_gain);
369  cam_params_.blue_gain = prevCamParams.blue_gain;
370  } else {
371  hasNewParams = true;
372  }
373  }
374  } else {
375  local_nh.setParam("blue_gain", cam_params_.blue_gain);
376  }
377  if (local_nh.hasParam("gain_boost")) {
378  local_nh.getParam("gain_boost", cam_params_.gain_boost);
379  if (cam_params_.gain_boost != prevCamParams.gain_boost) {
380  hasNewParams = true;
381  }
382  } else {
383  local_nh.setParam("gain_boost", cam_params_.gain_boost);
384  }
385  if (local_nh.hasParam("software_gamma")) {
386  local_nh.getParam("software_gamma", cam_params_.software_gamma);
387  if (cam_params_.software_gamma != prevCamParams.software_gamma) {
388  hasNewParams = true;
389  }
390  }
391  if (local_nh.hasParam("auto_exposure")) {
392  local_nh.getParam("auto_exposure", cam_params_.auto_exposure);
393  if (cam_params_.auto_exposure != prevCamParams.auto_exposure) {
394  hasNewParams = true;
395  }
396  } else {
397  local_nh.setParam("auto_exposure", cam_params_.auto_exposure);
398  }
399  if (local_nh.hasParam("auto_exposure_reference")) {
400  local_nh.getParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
401  if (cam_params_.auto_exposure_reference != prevCamParams.auto_exposure_reference) {
402  hasNewParams = true;
403  }
404  } else {
405  local_nh.setParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
406  }
407  if (local_nh.hasParam("exposure")) {
408  local_nh.getParam("exposure", cam_params_.exposure);
409  if (cam_params_.exposure != prevCamParams.exposure) {
410  if (cam_params_.exposure < 0.0) {
411  WARN_STREAM("Invalid requested exposure: " << cam_params_.exposure <<
412  "; using current exposure: " << prevCamParams.exposure);
413  cam_params_.exposure = prevCamParams.exposure;
414  } else {
415  hasNewParams = true;
416  }
417  }
418  } else {
419  local_nh.setParam("exposure", cam_params_.exposure);
420  }
421  if (local_nh.hasParam("auto_white_balance")) {
422  local_nh.getParam("auto_white_balance", cam_params_.auto_white_balance);
423  if (cam_params_.auto_white_balance != prevCamParams.auto_white_balance) {
424  hasNewParams = true;
425  }
426  } else {
427  local_nh.setParam("auto_white_balance", cam_params_.auto_white_balance);
428  }
429  if (local_nh.hasParam("white_balance_red_offset")) {
430  local_nh.getParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
431  if (cam_params_.white_balance_red_offset != prevCamParams.white_balance_red_offset) {
432  if (cam_params_.white_balance_red_offset < -50 || cam_params_.white_balance_red_offset > 50) {
433  WARN_STREAM("Invalid white balance red offset for [" << cam_name_ << "]: " <<
434  cam_params_.white_balance_red_offset <<
435  "; using current white balance red offset: " << prevCamParams.white_balance_red_offset);
436  cam_params_.white_balance_red_offset = prevCamParams.white_balance_red_offset;
437  } else {
438  hasNewParams = true;
439  }
440  }
441  } else {
442  local_nh.setParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
443  }
444  if (local_nh.hasParam("white_balance_blue_offset")) {
445  local_nh.getParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
446  if (cam_params_.white_balance_blue_offset != prevCamParams.white_balance_blue_offset) {
447  if (cam_params_.white_balance_blue_offset < -50 || cam_params_.white_balance_blue_offset > 50) {
448  WARN_STREAM("Invalid white balance blue offset for [" << cam_name_ << "]: " <<
449  cam_params_.white_balance_blue_offset <<
450  "; using current white balance blue offset: " << prevCamParams.white_balance_blue_offset);
451  cam_params_.white_balance_blue_offset = prevCamParams.white_balance_blue_offset;
452  } else {
453  hasNewParams = true;
454  }
455  }
456  } else {
457  local_nh.setParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
458  }
459  if (local_nh.hasParam("ext_trigger_mode")) {
460  local_nh.getParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
461  // NOTE: no need to set any parameters, since external trigger / live-run
462  // modes come into effect during frame grab loop, which is assumed
463  // to not having been initialized yet
464  } else {
465  local_nh.setParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
466  }
467  if (local_nh.hasParam("flash_delay")) {
468  local_nh.getParam("flash_delay", cam_params_.flash_delay);
469  // NOTE: no need to set any parameters, since flash delay comes into
470  // effect during frame grab loop, which is assumed to not having been
471  // initialized yet
472  } else {
473  local_nh.setParam("flash_delay", cam_params_.flash_delay);
474  }
475  if (local_nh.hasParam("flash_duration")) {
476  local_nh.getParam("flash_duration", cam_params_.flash_duration);
477  if (cam_params_.flash_duration < 0) {
478  WARN_STREAM("Invalid flash duration for [" << cam_name_ << "]: " <<
479  cam_params_.flash_duration <<
480  "; using current flash duration: " << prevCamParams.flash_duration);
481  cam_params_.flash_duration = prevCamParams.flash_duration;
482  }
483  // NOTE: no need to set any parameters, since flash duration comes into
484  // effect during frame grab loop, which is assumed to not having been
485  // initialized yet
486  } else {
487  local_nh.setParam("flash_duration", cam_params_.flash_duration);
488  }
489  if (local_nh.hasParam("gpio1")) {
490  local_nh.getParam("gpio1", cam_params_.gpio1);
491  if (cam_params_.gpio1 != prevCamParams.gpio1) {hasNewParams = true;}
492  } else {
493  local_nh.setParam("gpio1", cam_params_.gpio1);
494  }
495  if (local_nh.hasParam("gpio2")) {
496  local_nh.getParam("gpio2", cam_params_.gpio2);
497  if (cam_params_.gpio2 != prevCamParams.gpio2) {hasNewParams = true;}
498  } else {
499  local_nh.setParam("gpio2", cam_params_.gpio2);
500  }
501  if (local_nh.hasParam("pwm_freq")) {
502  local_nh.getParam("pwm_freq", cam_params_.pwm_freq);
503  if (cam_params_.pwm_freq != prevCamParams.pwm_freq) {hasNewParams = true;}
504  } else {
505  local_nh.setParam("pwm_freq", cam_params_.pwm_freq);
506  }
507  if (local_nh.hasParam("pwm_duty_cycle")) {
508  local_nh.getParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
509  if (cam_params_.pwm_duty_cycle != prevCamParams.pwm_duty_cycle) {hasNewParams = true;}
510  } else {
511  local_nh.setParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
512  }
513 
514  if (local_nh.hasParam("auto_frame_rate")) {
515  local_nh.getParam("auto_frame_rate", cam_params_.auto_frame_rate);
516  if (cam_params_.auto_frame_rate != prevCamParams.auto_frame_rate) {
517  hasNewParams = true;
518  }
519  } else {
520  local_nh.setParam("auto_frame_rate", cam_params_.auto_frame_rate);
521  }
522  if (local_nh.hasParam("frame_rate")) {
523  local_nh.getParam("frame_rate", cam_params_.frame_rate);
524  if (cam_params_.frame_rate != prevCamParams.frame_rate) {
525  if (cam_params_.frame_rate <= 0.0) {
526  WARN_STREAM("Invalid requested frame rate for [" << cam_name_ << "]: " <<
527  cam_params_.frame_rate <<
528  "; using current frame rate: " << prevCamParams.frame_rate);
529  cam_params_.frame_rate = prevCamParams.frame_rate;
530  } else {
531  hasNewParams = true;
532  }
533  }
534  } else {
535  local_nh.setParam("frame_rate", cam_params_.frame_rate);
536  }
537  if (local_nh.hasParam("output_rate")) {
538  local_nh.getParam("output_rate", cam_params_.output_rate);
539  if (cam_params_.output_rate < 0.0) {
540  WARN_STREAM("Invalid requested output rate for [" << cam_name_ << "]: " <<
541  cam_params_.output_rate <<
542  "; disable publisher throttling by default");
543  cam_params_.output_rate = 0;
544  } else {
545  cam_params_.output_rate = std::min(cam_params_.frame_rate, cam_params_.output_rate);
546  // hasNewParams = true; // No need to re-allocate buffer memory or reconfigure camera parameters
547  }
548  } else {
549  local_nh.setParam("output_rate", cam_params_.output_rate);
550  }
551  if (local_nh.hasParam("pixel_clock")) {
552  local_nh.getParam("pixel_clock", cam_params_.pixel_clock);
553  if (cam_params_.pixel_clock != prevCamParams.pixel_clock) {
554  if (cam_params_.pixel_clock < 0) {
555  WARN_STREAM("Invalid requested pixel clock for [" << cam_name_ << "]: " <<
556  cam_params_.pixel_clock <<
557  "; using current pixel clock: " << prevCamParams.pixel_clock);
558  cam_params_.pixel_clock = prevCamParams.pixel_clock;
559  } else {
560  hasNewParams = true;
561  }
562  }
563  } else {
564  local_nh.setParam("pixel_clock", cam_params_.pixel_clock);
565  }
566  if (local_nh.hasParam("flip_upd")) {
567  local_nh.getParam("flip_upd", cam_params_.flip_upd);
568  if (cam_params_.flip_upd != prevCamParams.flip_upd) {
569  hasNewParams = true;
570  }
571  } else {
572  local_nh.setParam("flip_upd", cam_params_.flip_upd);
573  }
574  if (local_nh.hasParam("flip_lr")) {
575  local_nh.getParam("flip_lr", cam_params_.flip_lr);
576  if (cam_params_.flip_lr != prevCamParams.flip_lr) {
577  hasNewParams = true;
578  }
579  } else {
580  local_nh.setParam("flip_lr", cam_params_.flip_lr);
581  }
582 
583  if (hasNewParams) {
584  // Configure color mode, resolution, and subsampling rate
585  // NOTE: this batch of configurations are mandatory, to ensure proper allocation of local frame buffer
586  if ((is_err = setColorMode(cam_params_.color_mode, false)) != IS_SUCCESS) return is_err;
587  if ((is_err = setSubsampling(cam_params_.subsampling, false)) != IS_SUCCESS) return is_err;
588  if ((is_err = setBinning(cam_params_.binning, false)) != IS_SUCCESS) return is_err;
589  if ((is_err = setResolution(cam_params_.image_width, cam_params_.image_height,
590  cam_params_.image_left, cam_params_.image_top, false)) != IS_SUCCESS) return is_err;
591  if ((is_err = setSensorScaling(cam_params_.sensor_scaling, false)) != IS_SUCCESS) return is_err;
592 
593  // Force synchronize settings and re-allocate frame buffer for redundancy
594  // NOTE: although this might not be needed, assume that parseROSParams()
595  // is called only once per nodelet, thus ignore cost
596  if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
597 
598  // Check for mutual exclusivity among requested sensor parameters
599  if (!cam_params_.auto_exposure) { // Auto frame rate requires auto shutter
600  cam_params_.auto_frame_rate = false;
601  }
602  if (cam_params_.auto_frame_rate) { // Auto frame rate has precedence over auto gain
603  cam_params_.auto_gain = false;
604  }
605 
606  // Configure camera sensor parameters
607  // NOTE: failing to configure certain parameters may or may not cause camera to fail;
608  // cuurently their failures are treated as non-critical
609  //#define noop return is_err
610  #define noop (void)0
611  if ((is_err = setGain(cam_params_.auto_gain, cam_params_.master_gain,
612  cam_params_.red_gain, cam_params_.green_gain,
613  cam_params_.blue_gain, cam_params_.gain_boost)) != IS_SUCCESS) noop;
614  if ((is_err = setSoftwareGamma(cam_params_.software_gamma)) != IS_SUCCESS) noop;
615  if ((is_err = setPixelClockRate(cam_params_.pixel_clock)) != IS_SUCCESS) return is_err;
616  if ((is_err = setFrameRate(cam_params_.auto_frame_rate, cam_params_.frame_rate)) != IS_SUCCESS) return is_err;
617  if ((is_err = setExposure(cam_params_.auto_exposure, cam_params_.auto_exposure_reference, cam_params_.exposure)) != IS_SUCCESS) noop;
618  if ((is_err = setWhiteBalance(cam_params_.auto_white_balance, cam_params_.white_balance_red_offset,
619  cam_params_.white_balance_blue_offset)) != IS_SUCCESS) noop;
620  if ((is_err = setGpioMode(1, cam_params_.gpio1, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
621  if ((is_err = setGpioMode(2, cam_params_.gpio2, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
622  if ((is_err = setMirrorUpsideDown(cam_params_.flip_upd)) != IS_SUCCESS) noop;
623  if ((is_err = setMirrorLeftRight(cam_params_.flip_lr)) != IS_SUCCESS) noop;
624  #undef noop
625  }
626 
627  DEBUG_STREAM("Successfully applied settings from ROS params to [" << cam_name_ << "]");
628 
629  return is_err;
630 }
631 
632 
633 void UEyeCamNodelet::configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level) {
634  if (!isConnected()) return;
635 
636  // See if frame grabber needs to be restarted
637  bool restartFrameGrabber = false;
638  bool needToReallocateBuffer = false;
639  if (level == RECONFIGURE_STOP && frame_grab_alive_) {
640  restartFrameGrabber = true;
642  }
643 
644  // Configure color mode, resolution, and subsampling rate
645  if (config.color_mode != cam_params_.color_mode) {
646  needToReallocateBuffer = true;
647  if (setColorMode(config.color_mode, false) != IS_SUCCESS) return;
648  }
649 
650  if (config.image_width != cam_params_.image_width ||
651  config.image_height != cam_params_.image_height ||
652  config.image_left != cam_params_.image_left ||
653  config.image_top != cam_params_.image_top) {
654  needToReallocateBuffer = true;
655  if (setResolution(config.image_width, config.image_height,
656  config.image_left, config.image_top, false) != IS_SUCCESS) {
657  // Attempt to restore previous (working) resolution
658  config.image_width = cam_params_.image_width;
659  config.image_height = cam_params_.image_height;
660  config.image_left = cam_params_.image_left;
661  config.image_top = cam_params_.image_top;
662  if (setResolution(config.image_width, config.image_height,
663  config.image_left, config.image_top, false) != IS_SUCCESS) return;
664  }
665  }
666 
667  if (config.subsampling != cam_params_.subsampling) {
668  needToReallocateBuffer = true;
669  if (setSubsampling(config.subsampling, false) != IS_SUCCESS) return;
670  }
671 
672  if (config.binning != cam_params_.binning) {
673  needToReallocateBuffer = true;
674  if (setBinning(config.binning, false) != IS_SUCCESS) return;
675  }
676 
677  if (config.sensor_scaling != cam_params_.sensor_scaling) {
678  needToReallocateBuffer = true;
679  if (setSensorScaling(config.sensor_scaling, false) != IS_SUCCESS) return;
680  }
681 
682  // Reallocate internal camera buffer, and synchronize both non-ROS and ROS settings
683  // for redundancy
684  if (needToReallocateBuffer) {
685  if (syncCamConfig() != IS_SUCCESS) return;
686  needToReallocateBuffer = false;
687  }
688 
689  // Check for mutual exclusivity among requested sensor parameters
690  if (!config.auto_exposure) { // Auto frame rate requires auto shutter
691  config.auto_frame_rate = false;
692  }
693  if (config.auto_frame_rate) { // Auto frame rate has precedence over auto gain
694  config.auto_gain = false;
695  }
696 
697  // Configure camera sensor parameters
698  if (config.auto_gain != cam_params_.auto_gain ||
699  config.master_gain != cam_params_.master_gain ||
700  config.red_gain != cam_params_.red_gain ||
701  config.green_gain != cam_params_.green_gain ||
702  config.blue_gain != cam_params_.blue_gain ||
703  config.gain_boost != cam_params_.gain_boost) {
704  // If any of the manual gain params change, then automatically toggle off auto_gain
705  if (config.master_gain != cam_params_.master_gain ||
706  config.red_gain != cam_params_.red_gain ||
707  config.green_gain != cam_params_.green_gain ||
708  config.blue_gain != cam_params_.blue_gain ||
709  config.gain_boost != cam_params_.gain_boost) {
710  config.auto_gain = false;
711  }
712 
713  if (setGain(config.auto_gain, config.master_gain,
714  config.red_gain, config.green_gain,
715  config.blue_gain, config.gain_boost) != IS_SUCCESS) return;
716  }
717  if (config.software_gamma != cam_params_.software_gamma) {
718  if (setSoftwareGamma(config.software_gamma) != IS_SUCCESS) return;
719  }
720 
721 
722  if (config.pixel_clock != cam_params_.pixel_clock) {
723  if (setPixelClockRate(config.pixel_clock) != IS_SUCCESS) return;
724  }
725 
726  if (config.auto_frame_rate != cam_params_.auto_frame_rate ||
727  config.frame_rate != cam_params_.frame_rate) {
728  if (setFrameRate(config.auto_frame_rate, config.frame_rate) != IS_SUCCESS) return;
729  }
730 
731  if (config.output_rate != cam_params_.output_rate) {
732  if (!config.auto_frame_rate) {
733  config.output_rate = std::min(config.output_rate, config.frame_rate);
734  } // else, auto-fps is enabled, so don't bother checking validity of user-specified config.output_rate
735 
736  // Reset reference time for publisher throttle
737  output_rate_mutex_.lock();
740  output_rate_mutex_.unlock();
741  }
742 
743  if (config.auto_exposure != cam_params_.auto_exposure ||
744  config.auto_exposure_reference != cam_params_.auto_exposure_reference ||
745  config.exposure != cam_params_.exposure) {
746  if (setExposure(config.auto_exposure, config.auto_exposure_reference, config.exposure) != IS_SUCCESS) return;
747  }
748 
749  if (config.auto_white_balance != cam_params_.auto_white_balance ||
750  config.white_balance_red_offset != cam_params_.white_balance_red_offset ||
751  config.white_balance_blue_offset != cam_params_.white_balance_blue_offset) {
752  if (setWhiteBalance(config.auto_white_balance, config.white_balance_red_offset,
753  config.white_balance_blue_offset) != IS_SUCCESS) return;
754  }
755 
756  if (config.flip_upd != cam_params_.flip_upd) {
757  if (setMirrorUpsideDown(config.flip_upd) != IS_SUCCESS) return;
758  }
759  if (config.flip_lr != cam_params_.flip_lr) {
760  if (setMirrorLeftRight(config.flip_lr) != IS_SUCCESS) return;
761  }
762 
763  // NOTE: nothing needs to be done for config.ext_trigger_mode, since frame grabber loop will re-initialize to the right setting
764 
765  if (config.flash_delay != cam_params_.flash_delay ||
766  config.flash_duration != cam_params_.flash_duration) {
767  // NOTE: need to copy flash parameters to local copies since
768  // cam_params_.flash_duration is type int, and also sizeof(int)
769  // may not equal to sizeof(INT) / sizeof(UINT)
770  INT flash_delay = config.flash_delay;
771  UINT flash_duration = static_cast<UINT>(config.flash_duration);
772  setFlashParams(flash_delay, flash_duration);
773  // Copy back actual flash parameter values that were set
774  config.flash_delay = flash_delay;
775  config.flash_duration = static_cast<int>(flash_duration);
776  }
777 
778  // Change gpio if mode has changed OR if mode is pwm and pwm settings have been changed
779  if ((config.gpio1 != cam_params_.gpio1) ||
780  (config.gpio1 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
781  if (setGpioMode(1, config.gpio1, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
782  }
783  if ((config.gpio2 != cam_params_.gpio2) ||
784  (config.gpio2 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
785  if (setGpioMode(2, config.gpio2, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
786  }
787 
788  // Update local copy of parameter set to newly updated set
789  cam_params_ = config;
790 
791  // Restart frame grabber if needed
792  cfg_sync_requested_ = true;
793  if (restartFrameGrabber) {
795  }
796 
797  DEBUG_STREAM("Successfully applied settings from dyncfg to [" << cam_name_ << "]");
798 }
799 
800 
801 INT UEyeCamNodelet::syncCamConfig(string dft_mode_str) {
802  INT is_err;
803 
804  if ((is_err = UEyeCamDriver::syncCamConfig(dft_mode_str)) != IS_SUCCESS) return is_err;
805 
806  // Update ROS color mode string
807  cam_params_.color_mode = colormode2name(is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE));
808  if (cam_params_.color_mode.empty()) {
809  ERROR_STREAM("Force-updating to default color mode for [" << cam_name_ << "]: " <<
810  dft_mode_str << "\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
811  cam_params_.color_mode = dft_mode_str;
812  setColorMode(cam_params_.color_mode);
813  }
814 
815  // Copy internal settings to ROS dynamic configure settings
816  cam_params_.image_width = cam_aoi_.s32Width; // Technically, these are width and height for the
817  cam_params_.image_height = cam_aoi_.s32Height; // sensor's Area of Interest, and not of the image
818  if (cam_params_.image_left >= 0) cam_params_.image_left = cam_aoi_.s32X; // TODO: 1 ideally want to ensure that aoi top-left does correspond to centering
819  if (cam_params_.image_top >= 0) cam_params_.image_top = cam_aoi_.s32Y;
820  cam_params_.subsampling = static_cast<int>(cam_subsampling_rate_);
821  cam_params_.binning = static_cast<int>(cam_binning_rate_);
822  cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
823  //cfg_sync_requested_ = true; // WARNING: assume that dyncfg client may want to override current settings
824 
825  // (Re-)populate ROS image message
826  ros_image_.header.frame_id = frame_name_;
827  // NOTE: .height, .width, .encoding, .step and .data determined in fillImgMsg();
828  // .is_bigendian determined in constructor
829 
830  return is_err;
831 }
832 
833 
835  INT is_err = IS_SUCCESS;
836  INT query;
837  double pval1, pval2;
838 
839  // NOTE: assume that color mode, bits per pixel, area of interest info, resolution,
840  // sensor scaling rate, subsampling rate, and binning rate have already
841  // been synchronized by syncCamConfig()
842 
843  if ((is_err = is_SetAutoParameter(cam_handle_,
844  IS_GET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS &&
845  (is_err = is_SetAutoParameter(cam_handle_,
846  IS_GET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
847  ERROR_STREAM("Failed to query auto gain mode for UEye camera '" <<
848  cam_name_ << "' (" << err2str(is_err) << ")");
849  return is_err;
850  }
851  cam_params_.auto_gain = (pval1 != 0);
852 
853  cam_params_.master_gain = is_SetHardwareGain(cam_handle_, IS_GET_MASTER_GAIN,
854  IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
855  cam_params_.red_gain = is_SetHardwareGain(cam_handle_, IS_GET_RED_GAIN,
856  IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
857  cam_params_.green_gain = is_SetHardwareGain(cam_handle_, IS_GET_GREEN_GAIN,
858  IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
859  cam_params_.blue_gain = is_SetHardwareGain(cam_handle_, IS_GET_BLUE_GAIN,
860  IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
861 
862  query = is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST);
863  if(query == IS_SET_GAINBOOST_ON) {
864  query = is_SetGainBoost(cam_handle_, IS_GET_GAINBOOST);
865  if (query == IS_SET_GAINBOOST_ON) {
866  cam_params_.gain_boost = true;
867  } else if (query == IS_SET_GAINBOOST_OFF) {
868  cam_params_.gain_boost = false;
869  } else {
870  ERROR_STREAM("Failed to query gain boost for [" << cam_name_ <<
871  "] (" << err2str(query) << ")");
872  return query;
873  }
874  } else {
875  cam_params_.gain_boost = false;
876  }
877 
878  if ((is_err = is_Gamma(cam_handle_, IS_GAMMA_CMD_GET, (void*) &cam_params_.software_gamma,
879  sizeof(cam_params_.software_gamma))) != IS_SUCCESS) {
880  ERROR_STREAM("Failed to query software gamma value for [" << cam_name_ <<
881  "] (" << err2str(is_err) << ")");
882  return is_err;
883  }
884 
885  if ((is_err = is_SetAutoParameter(cam_handle_,
886  IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS &&
887  (is_err = is_SetAutoParameter(cam_handle_,
888  IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
889  ERROR_STREAM("Failed to query auto shutter mode for [" << cam_name_ <<
890  "] (" << err2str(is_err) << ")");
891  return is_err;
892  }
893  cam_params_.auto_exposure = (pval1 != 0);
894 
895  if ((is_err = is_SetAutoParameter (cam_handle_, IS_GET_AUTO_REFERENCE,
896  &cam_params_.auto_exposure_reference, 0)) != IS_SUCCESS) {
897  ERROR_STREAM("Failed to query exposure reference value for [" << cam_name_ <<
898  "] (" << err2str(is_err) << ")");
899  }
900 
901  if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE,
902  &cam_params_.exposure, sizeof(cam_params_.exposure))) != IS_SUCCESS) {
903  ERROR_STREAM("Failed to query exposure timing for [" << cam_name_ <<
904  "] (" << err2str(is_err) << ")");
905  return is_err;
906  }
907 
908  if ((is_err = is_SetAutoParameter(cam_handle_,
909  IS_GET_ENABLE_AUTO_SENSOR_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS &&
910  (is_err = is_SetAutoParameter(cam_handle_,
911  IS_GET_ENABLE_AUTO_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS) {
912  ERROR_STREAM("Failed to query auto white balance mode for [" << cam_name_ <<
913  "] (" << err2str(is_err) << ")");
914  return is_err;
915  }
916  cam_params_.auto_white_balance = (pval1 != 0);
917 
918  if ((is_err = is_SetAutoParameter(cam_handle_,
919  IS_GET_AUTO_WB_OFFSET, &pval1, &pval2)) != IS_SUCCESS) {
920  ERROR_STREAM("Failed to query auto white balance red/blue channel offsets for [" <<
921  cam_name_ << "] (" << err2str(is_err) << ")");
922  return is_err;
923  }
924  cam_params_.white_balance_red_offset = static_cast<int>(pval1);
925  cam_params_.white_balance_blue_offset = static_cast<int>(pval2);
926 
927  IO_FLASH_PARAMS currFlashParams;
928  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS,
929  (void*) &currFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
930  ERROR_STREAM("Could not retrieve current flash parameter info for [" <<
931  cam_name_ << "] (" << err2str(is_err) << ")");
932  return is_err;
933  }
934  cam_params_.flash_delay = currFlashParams.s32Delay;
935  cam_params_.flash_duration = static_cast<int>(currFlashParams.u32Duration);
936 
937  if ((is_err = is_SetAutoParameter(cam_handle_,
938  IS_GET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS &&
939  (is_err = is_SetAutoParameter(cam_handle_,
940  IS_GET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
941  ERROR_STREAM("Failed to query auto frame rate mode for [" << cam_name_ <<
942  "] (" << err2str(is_err) << ")");
943  return is_err;
944  }
945  cam_params_.auto_frame_rate = (pval1 != 0);
946 
947  if ((is_err = is_SetFrameRate(cam_handle_, IS_GET_FRAMERATE, &cam_params_.frame_rate)) != IS_SUCCESS) {
948  ERROR_STREAM("Failed to query frame rate for [" << cam_name_ <<
949  "] (" << err2str(is_err) << ")");
950  return is_err;
951  }
952 
953  UINT currPixelClock;
954  if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET,
955  (void*) &currPixelClock, sizeof(currPixelClock))) != IS_SUCCESS) {
956  ERROR_STREAM("Failed to query pixel clock rate for [" << cam_name_ <<
957  "] (" << err2str(is_err) << ")");
958  return is_err;
959  }
960  cam_params_.pixel_clock = static_cast<int>(currPixelClock);
961 
962  INT currROP = is_SetRopEffect(cam_handle_, IS_GET_ROP_EFFECT, 0, 0);
963  cam_params_.flip_upd = ((currROP & IS_SET_ROP_MIRROR_UPDOWN) == IS_SET_ROP_MIRROR_UPDOWN);
964  cam_params_.flip_lr = ((currROP & IS_SET_ROP_MIRROR_LEFTRIGHT) == IS_SET_ROP_MIRROR_LEFTRIGHT);
965 
966  // NOTE: do not need to (re-)populate ROS image message, since assume that
967  // syncCamConfig() was previously called
968 
969  DEBUG_STREAM("Successfully queries parameters from [" << cam_name_ << "]");
970 
971  return is_err;
972 }
973 
974 
976  INT is_err = IS_SUCCESS;
977 
978  if ((is_err = UEyeCamDriver::connectCam()) != IS_SUCCESS) return is_err;
979 
980  // (Attempt to) load UEye camera parameter configuration file
981  if (cam_params_filename_.length() <= 0) { // Use default filename
982  cam_params_filename_ = string(getenv("HOME")) + "/.ros/camera_conf/" + cam_name_ + ".ini";
983  }
984  if ((is_err = loadCamConfig(cam_params_filename_)) != IS_SUCCESS) return is_err;
985 
986  // Query existing configuration parameters from camera
987  if ((is_err = queryCamParams()) != IS_SUCCESS) return is_err;
988 
989  // Parse and load ROS camera settings
990  if ((is_err = parseROSParams(getPrivateNodeHandle())) != IS_SUCCESS) return is_err;
991 
992  return IS_SUCCESS;
993 }
994 
995 
997  INT is_err = IS_SUCCESS;
998 
999  if (isConnected()) {
1000  stopFrameGrabber();
1001  is_err = UEyeCamDriver::disconnectCam();
1002  }
1003 
1004  return is_err;
1005 }
1006 
1007 
1008 bool UEyeCamNodelet::setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
1009  sensor_msgs::SetCameraInfo::Response& rsp) {
1010  ros_cam_info_ = req.camera_info;
1011  ros_cam_info_.header.frame_id = frame_name_;
1012  rsp.success = saveIntrinsicsFile();
1013  rsp.status_message = (rsp.success) ?
1014  "successfully wrote camera info to file" :
1015  "failed to write camera info to file";
1016  return true;
1017 }
1018 
1019 
1021 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1022  ros::Time prevStartGrab = ros::Time::now();
1023  ros::Time prevGrabbedFrame = ros::Time::now();
1024  ros::Time currStartGrab;
1025  ros::Time currGrabbedFrame;
1026  double startGrabSum = 0;
1027  double grabbedFrameSum = 0;
1028  double startGrabSumSqrd = 0;
1029  double grabbedFrameSumSqrd = 0;
1030  unsigned int startGrabCount = 0;
1031  unsigned int grabbedFrameCount = 0;
1032 #endif
1033 
1034  DEBUG_STREAM("Starting threaded frame grabber loop for [" << cam_name_ << "]");
1035 
1036  ros::Rate idleDelay(200);
1037 
1038  int prevNumSubscribers = 0;
1039  int currNumSubscribers = 0;
1040  while (frame_grab_alive_ && ros::ok()) {
1041  // Initialize live video mode if camera was previously asleep, and ROS image topic has subscribers;
1042  // and stop live video mode if ROS image topic no longer has any subscribers
1043  currNumSubscribers = static_cast<int>(ros_cam_pub_.getNumSubscribers());
1044  if (currNumSubscribers > 0 && prevNumSubscribers <= 0) {
1045  // Reset reference time to prevent throttling first frame
1046  output_rate_mutex_.lock();
1049  output_rate_mutex_.unlock();
1050 
1051  if (cam_params_.ext_trigger_mode) {
1052  if (setExtTriggerMode() != IS_SUCCESS) {
1053  ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1054  ros::shutdown();
1055  return;
1056  }
1057  INFO_STREAM("[" << cam_name_ << "] set to external trigger mode");
1058  } else {
1059  if (setFreeRunMode() != IS_SUCCESS) {
1060  ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1061  ros::shutdown();
1062  return;
1063  }
1064 
1065  // NOTE: need to copy flash parameters to local copies since
1066  // cam_params_.flash_duration is type int, and also sizeof(int)
1067  // may not equal to sizeof(INT) / sizeof(UINT)
1068  INT flash_delay = cam_params_.flash_delay;
1069  UINT flash_duration = static_cast<unsigned int>(cam_params_.flash_duration);
1070  setFlashParams(flash_delay, flash_duration);
1071  // Copy back actual flash parameter values that were set
1072  cam_params_.flash_delay = flash_delay;
1073  cam_params_.flash_duration = static_cast<int>(flash_duration);
1074 
1075  INFO_STREAM("[" << cam_name_ << "] set to free-run mode");
1076  }
1077  } else if (currNumSubscribers <= 0 && prevNumSubscribers > 0) {
1078  if (setStandbyMode() != IS_SUCCESS) {
1079  ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
1080  ros::shutdown();
1081  return;
1082  }
1083  INFO_STREAM("[" << cam_name_ << "] set to standby mode");
1084  }
1085  prevNumSubscribers = currNumSubscribers;
1086 
1087  // Send updated dyncfg parameters if previously changed
1088  if (cfg_sync_requested_) {
1089  if (ros_cfg_mutex_.try_lock()) { // Make sure that dynamic reconfigure server or config callback is not active
1090  ros_cfg_mutex_.unlock();
1091  ros_cfg_->updateConfig(cam_params_);
1092  cfg_sync_requested_ = false;
1093  }
1094  }
1095 
1096 
1097 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1098  startGrabCount++;
1099  currStartGrab = ros::Time::now();
1100  if (startGrabCount > 1) {
1101  startGrabSum += (currStartGrab - prevStartGrab).toSec() * 1000.0;
1102  startGrabSumSqrd += ((currStartGrab - prevStartGrab).toSec() * 1000.0)*((currStartGrab - prevStartGrab).toSec() * 1000.0);
1103  }
1104  prevStartGrab = currStartGrab;
1105 #endif
1106 
1107  if (isCapturing()) {
1108  UINT eventTimeout = (cam_params_.auto_frame_rate || cam_params_.ext_trigger_mode) ?
1109  static_cast<INT>(2000) : static_cast<INT>(1000.0 / cam_params_.frame_rate * 2);
1110  if (processNextFrame(eventTimeout) != nullptr) {
1111  // Initialize shared pointers from member messages for nodelet intraprocess publishing
1112  sensor_msgs::ImagePtr img_msg_ptr(new sensor_msgs::Image(ros_image_));
1113  sensor_msgs::CameraInfoPtr cam_info_msg_ptr(new sensor_msgs::CameraInfo(ros_cam_info_));
1114 
1115  // Initialize/compute frame timestamp based on clock tick value from camera
1116  if (init_ros_time_.isZero()) {
1119  }
1120  }
1121  img_msg_ptr->header.stamp = cam_info_msg_ptr->header.stamp = getImageTickTimestamp();
1122 
1123  // Process new frame
1124 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
1125  grabbedFrameCount++;
1126  currGrabbedFrame = ros::Time::now();
1127  if (grabbedFrameCount > 1) {
1128  grabbedFrameSum += (currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0;
1129  grabbedFrameSumSqrd += ((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0)*((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0);
1130  }
1131  prevGrabbedFrame = currGrabbedFrame;
1132 
1133  if (grabbedFrameCount > 1) {
1134  WARN_STREAM("\nPre-Grab: " << startGrabSum/startGrabCount << " +/- " <<
1135  sqrt(startGrabSumSqrd/startGrabCount - (startGrabSum/startGrabCount)*(startGrabSum/startGrabCount)) << " ms (" <<
1136  1000.0*startGrabCount/startGrabSum << "Hz)\n" <<
1137  "Post-Grab: " << grabbedFrameSum/grabbedFrameCount << " +/- " <<
1138  sqrt(grabbedFrameSumSqrd/grabbedFrameCount - (grabbedFrameSum/grabbedFrameCount)*(grabbedFrameSum/grabbedFrameCount)) << " ms (" <<
1139  1000.0*grabbedFrameCount/grabbedFrameSum << "Hz)\n" <<
1140  "Target: " << cam_params_.frame_rate << "Hz");
1141  }
1142 #endif
1143 
1144  if (!frame_grab_alive_ || !ros::ok()) break;
1145 
1146  // Throttle publish rate
1147  bool throttle_curr_frame = false;
1148  output_rate_mutex_.lock();
1149  if (!cam_params_.ext_trigger_mode && cam_params_.output_rate > 0) {
1150  if (init_publish_time_.is_zero()) { // Set reference time
1151  init_publish_time_ = img_msg_ptr->header.stamp;
1152  } else {
1153  double time_elapsed = (img_msg_ptr->header.stamp - init_publish_time_).toSec();
1154  uint64_t curr_output_frame_idx = static_cast<uint64_t>(std::floor(time_elapsed * cam_params_.output_rate));
1155  if (curr_output_frame_idx <= prev_output_frame_idx_) {
1156  throttle_curr_frame = true;
1157  } else {
1158  prev_output_frame_idx_ = curr_output_frame_idx;
1159  }
1160  }
1161  }
1162  output_rate_mutex_.unlock();
1163  if (throttle_curr_frame) continue;
1164 
1165  cam_info_msg_ptr->width = static_cast<unsigned int>(cam_params_.image_width / cam_sensor_scaling_rate_ / cam_binning_rate_ / cam_subsampling_rate_);
1166  cam_info_msg_ptr->height = static_cast<unsigned int>(cam_params_.image_height / cam_sensor_scaling_rate_ / cam_binning_rate_ / cam_subsampling_rate_);
1167 
1168  // Copy pixel content from internal frame buffer to ROS image
1169  if (!fillMsgData(*img_msg_ptr)) continue;
1170 
1171  img_msg_ptr->header.seq = cam_info_msg_ptr->header.seq = ros_frame_count_++;
1172  img_msg_ptr->header.frame_id = cam_info_msg_ptr->header.frame_id;
1173 
1174  if (!frame_grab_alive_ || !ros::ok()) break;
1175 
1176  ros_cam_pub_.publish(img_msg_ptr, cam_info_msg_ptr);
1177  }
1178  } else {
1180  init_clock_tick_ = 0;
1181  }
1182 
1183  if (!frame_grab_alive_ || !ros::ok()) break;
1184  idleDelay.sleep();
1185  }
1186 
1187  setStandbyMode();
1188  frame_grab_alive_ = false;
1189 
1190  DEBUG_STREAM("Frame grabber loop terminated for [" << cam_name_ << "]");
1191 }
1192 
1193 
1195  frame_grab_alive_ = true;
1196  frame_grab_thread_ = thread(bind(&UEyeCamNodelet::frameGrabLoop, this));
1197 }
1198 
1199 
1201  frame_grab_alive_ = false;
1202  if (frame_grab_thread_.joinable()) {
1203  frame_grab_thread_.join();
1204  }
1205  frame_grab_thread_ = thread();
1206 }
1207 
1208 const std::map<INT, std::string> UEyeCamNodelet::ENCODING_DICTIONARY = {
1209  { IS_CM_SENSOR_RAW8, sensor_msgs::image_encodings::BAYER_RGGB8 },
1210  { IS_CM_SENSOR_RAW10, sensor_msgs::image_encodings::BAYER_RGGB16 },
1211  { IS_CM_SENSOR_RAW12, sensor_msgs::image_encodings::BAYER_RGGB16 },
1212  { IS_CM_SENSOR_RAW16, sensor_msgs::image_encodings::BAYER_RGGB16 },
1213  { IS_CM_MONO8, sensor_msgs::image_encodings::MONO8 },
1214  { IS_CM_MONO10, sensor_msgs::image_encodings::MONO16 },
1215  { IS_CM_MONO12, sensor_msgs::image_encodings::MONO16 },
1216  { IS_CM_MONO16, sensor_msgs::image_encodings::MONO16 },
1217  { IS_CM_RGB8_PACKED, sensor_msgs::image_encodings::RGB8 },
1218  { IS_CM_BGR8_PACKED, sensor_msgs::image_encodings::BGR8 },
1219  { IS_CM_RGB10_PACKED, sensor_msgs::image_encodings::RGB16 },
1220  { IS_CM_BGR10_PACKED, sensor_msgs::image_encodings::BGR16 },
1221  { IS_CM_RGB10_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1222  { IS_CM_BGR10_UNPACKED, sensor_msgs::image_encodings::BGR16 },
1223  { IS_CM_RGB12_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1224  { IS_CM_BGR12_UNPACKED, sensor_msgs::image_encodings::BGR16 }
1225 };
1226 
1227 bool UEyeCamNodelet::fillMsgData(sensor_msgs::Image& img) const {
1228  // Copy pixel content from internal frame buffer to img
1229  // and unpack to proper pixel format
1230  INT expected_row_stride = cam_aoi_.s32Width * bits_per_pixel_/8;
1231  if (cam_buffer_pitch_ < expected_row_stride) {
1232  ERROR_STREAM("Camera buffer pitch (" << cam_buffer_pitch_ <<
1233  ") is smaller than expected for [" << cam_name_ << "]: " <<
1234  "width (" << cam_aoi_.s32Width << ") * bytes per pixel (" <<
1235  bits_per_pixel_/8 << ") = " << expected_row_stride);
1236  return false;
1237  }
1238 
1239  // allocate target memory
1240  img.width = static_cast<unsigned int>(cam_aoi_.s32Width);
1241  img.height = static_cast<unsigned int>(cam_aoi_.s32Height);
1242  img.encoding = ENCODING_DICTIONARY.at(color_mode_);
1243  img.step = img.width * static_cast<unsigned int>(sensor_msgs::image_encodings::numChannels(img.encoding)) * static_cast<unsigned int>(sensor_msgs::image_encodings::bitDepth(img.encoding))/8;
1244  img.data.resize(img.height * img.step);
1245 
1246  DEBUG_STREAM("Allocated ROS image buffer for [" << cam_name_ << "]:" <<
1247  "\n size: " << cam_buffer_size_ <<
1248  "\n width: " << img.width <<
1249  "\n height: " << img.height <<
1250  "\n step: " << img.step <<
1251  "\n encoding: " << img.encoding);
1252 
1253  const std::function<void*(void*, void*, size_t)> unpackCopy = getUnpackCopyFunc(color_mode_);
1254 
1255  if (cam_buffer_pitch_ == expected_row_stride) {
1256  // Content is contiguous, so copy out the entire buffer at once
1257  unpackCopy(img.data.data(), cam_buffer_, img.height*static_cast<unsigned int>(expected_row_stride));
1258  } else { // cam_buffer_pitch_ > expected_row_stride
1259  // Each row contains extra buffer according to cam_buffer_pitch_, so must copy out each row independently
1260  uint8_t* dst_ptr = img.data.data();
1261  char* cam_buffer_ptr = cam_buffer_;
1262  for (INT row = 0; row < cam_aoi_.s32Height; row++) {
1263  unpackCopy(dst_ptr, cam_buffer_ptr, static_cast<unsigned long>(expected_row_stride));
1264  cam_buffer_ptr += cam_buffer_pitch_;
1265  dst_ptr += img.step;
1266  }
1267  }
1268  return true;
1269 }
1270 
1271 
1273  if (cam_intr_filename_.length() <= 0) { // Use default filename
1274  cam_intr_filename_ = string(getenv("HOME")) + "/.ros/camera_info/" + cam_name_ + ".yaml";
1275  }
1276 
1278  DEBUG_STREAM("Loaded intrinsics parameters for [" << cam_name_ << "]");
1279  }
1280  ros_cam_info_.header.frame_id = frame_name_;
1281 }
1282 
1283 
1286  DEBUG_STREAM("Saved intrinsics parameters for [" << cam_name_ <<
1287  "] to " << cam_intr_filename_);
1288  return true;
1289  }
1290  return false;
1291 }
1292 
1294  // There have been several issues reported on time drifts, so we shall rely purely on ros::Time::now()
1295  // e.g. https://github.com/anqixu/ueye_cam/issues/82
1296  //
1297  // UEYETIME utime;
1298  // if(getTimestamp(&utime)) {
1299  // struct tm tm;
1300  // tm.tm_year = utime.wYear - 1900;
1301  // tm.tm_mon = utime.wMonth - 1;
1302  // tm.tm_mday = utime.wDay;
1303  // tm.tm_hour = utime.wHour;
1304  // tm.tm_min = utime.wMinute;
1305  // tm.tm_sec = utime.wSecond;
1306  // ros::Time t = ros::Time(mktime(&tm),utime.wMilliseconds*1e6);
1307  //
1308  // // Deal with instability due to daylight savings time
1309  // if (abs((ros::Time::now() - t).toSec()) > abs((ros::Time::now() - (t+ros::Duration(3600,0))).toSec())) { t += ros::Duration(3600,0); }
1310  // if (abs((ros::Time::now() - t).toSec()) > abs((ros::Time::now() - (t-ros::Duration(3600,0))).toSec())) { t -= ros::Duration(3600,0); }
1311  //
1312  // return t;
1313  // }
1314  return ros::Time::now();
1315 }
1316 
1318  uint64_t tick;
1319  if(getClockTick(&tick)) {
1320  return init_ros_time_ + ros::Duration(double(tick - init_clock_tick_)*1e-7);
1321  }
1322  return ros::Time::now();
1323 }
1324 // TODO: 0 bug where nodelet locks and requires SIGTERM when there are still subscribers (need to find where does code hang)
1325 
1326 
1328  std_msgs::UInt64 timeout_msg;
1329  timeout_msg.data = ++timeout_count_;
1330  timeout_pub_.publish(timeout_msg);
1331 };
1332 
1333 
1334 } // namespace ueye_cam
1335 
1336 
1337 // TODO: 9 bug: when binning (and suspect when subsampling / sensor scaling), white balance / color gains seem to have different effects
1338 
1339 
virtual INT connectCam(int new_cam_ID=-1)
static constexpr unsigned int RECONFIGURE_STOP
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
const char * processNextFrame(UINT timeout_ms)
INT setExposure(bool &auto_exposure, double &auto_exposure_reference, double &exposure_ms)
static const std::string colormode2name(INT mode)
static const std::function< void *(void *, void *, size_t)> getUnpackCopyFunc(INT color_mode)
bool fillMsgData(sensor_msgs::Image &img) const
def readCalibration(file_name)
void publish(const boost::shared_ptr< M > &message) const
static constexpr int DEFAULT_IMAGE_WIDTH
INT setMirrorLeftRight(bool flip_vertical)
f
static constexpr int ANY_CAMERA
static const std::string DEFAULT_FRAME_NAME
dynamic_reconfigure::Server< ueye_cam::UEyeCamConfig > ReconfigureServer
const std::string BAYER_RGGB16
static constexpr int DEFAULT_PIXEL_CLOCK
ReconfigureServer * ros_cfg_
uint32_t getNumSubscribers() const
INT setFlashParams(INT &delay_us, UINT &duration_us)
#define WARN_STREAM(...)
INT setGpioMode(const INT &gpio, INT &mode, double &pwm_freq, double &pwm_duty_cycle)
INT setWhiteBalance(bool &auto_white_balance, INT &red_offset, INT &blue_offset)
INT setColorMode(std::string &mode, bool reallocate_buffer=true)
INT setMirrorUpsideDown(bool flip_horizontal)
#define INFO_STREAM(...)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static constexpr int DEFAULT_FLASH_DURATION
static const std::map< INT, std::string > ENCODING_DICTIONARY
ros::NodeHandle & getPrivateNodeHandle() const
bool setCamInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
#define DEBUG_STREAM(...)
INT setSensorScaling(double &rate, bool reallocate_buffer=true)
#define ERROR_STREAM(...)
INT setPixelClockRate(INT &clock_rate_mhz)
void configCallback(ueye_cam::UEyeCamConfig &config, uint32_t level)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
static INT name2colormode(const std::string &name)
static const char * err2str(INT error)
unsigned int cam_subsampling_rate_
static const std::string DEFAULT_CAMERA_NAME
bool param(const std::string &param_name, T &param_val, const T &default_val) const
INT setSubsampling(int &rate, bool reallocate_buffer=true)
#define noop
ROSCPP_DECL bool ok()
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
INT setResolution(INT &image_width, INT &image_height, INT &image_left, INT &image_top, bool reallocate_buffer=true)
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const std::string MONO16
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
ros::NodeHandle & getNodeHandle() const
INT parseROSParams(ros::NodeHandle &local_nh)
boost::recursive_mutex ros_cfg_mutex_
static constexpr double DEFAULT_EXPOSURE
bool sleep()
sensor_msgs::Image ros_image_
static const std::string DEFAULT_CAMERA_TOPIC
sensor_msgs::CameraInfo ros_cam_info_
static int numChannels(const std::string &encoding)
ueye_cam::UEyeCamConfig cam_params_
bool getParam(const std::string &key, std::string &s) const
unsigned long long int timeout_count_
INT setBinning(int &rate, bool reallocate_buffer=true)
static Time now()
INT setFrameRate(bool &auto_frame_rate, double &frame_rate_hz)
ROSCPP_DECL void shutdown()
static const std::string DEFAULT_COLOR_MODE
const std::string BAYER_RGGB8
static int bitDepth(const std::string &encoding)
bool hasParam(const std::string &key) const
static constexpr double DEFAULT_FRAME_RATE
static constexpr int DEFAULT_IMAGE_HEIGHT
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool getClockTick(uint64_t *tick)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
image_transport::CameraPublisher ros_cam_pub_
INT setSoftwareGamma(INT &software_gamma)
std::string getTopic() const
static const std::string DEFAULT_TIMEOUT_TOPIC
INT loadCamConfig(std::string filename, bool ignore_load_failure=true)
ros::ServiceServer set_cam_info_srv_
INT setGain(bool &auto_gain, INT &master_gain_prc, INT &red_gain_prc, INT &green_gain_prc, INT &blue_gain_prc, bool &gain_boost)


ueye_cam
Author(s): Anqi Xu
autogenerated on Fri Jan 22 2021 03:34:12