ueye_cam_driver.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 
50 
51 using namespace std;
52 
53 
54 namespace ueye_cam {
55 
56 
57 // Note that all of these default settings will be overwritten
58 // by syncCamConfig() during connectCam()
59 UEyeCamDriver::UEyeCamDriver(int cam_ID, string cam_name):
60  cam_handle_(HIDS(0)),
61  cam_buffer_(nullptr),
62  cam_buffer_id_(0),
63  cam_buffer_pitch_(0),
64  cam_buffer_size_(0),
65  cam_name_(cam_name),
66  cam_id_(cam_ID),
67  cam_subsampling_rate_(1),
68  cam_binning_rate_(1),
69  cam_sensor_scaling_rate_(1),
70  color_mode_(IS_CM_MONO8),
71  bits_per_pixel_(8) {
72  cam_aoi_.s32X = 0;
73  cam_aoi_.s32Y = 0;
74  cam_aoi_.s32Width = 640;
75  cam_aoi_.s32Height = 480;
76 }
77 
78 
80  disconnectCam();
81 }
82 
83 
84 INT UEyeCamDriver::connectCam(int new_cam_ID) {
85  INT is_err = IS_SUCCESS;
86  int numCameras;
87 
88  // Terminate any existing opened cameras
90 
91  // Updates camera ID if specified.
92  if (new_cam_ID >= 0) {
93  cam_id_ = new_cam_ID;
94  }
95 
96  // Query for number of connected cameras
97  if ((is_err = is_GetNumberOfCameras(&numCameras)) != IS_SUCCESS) {
98  ERROR_STREAM("Failed query for number of connected UEye cameras (" <<
99  err2str(is_err) << ")");
100  return is_err;
101  } else if (numCameras < 1) {
102  ERROR_STREAM("No UEye cameras are connected\n");
103  ERROR_STREAM("Hint: make sure that the IDS camera daemon (/etc/init.d/ueyeusbdrc) is running\n");
104  return IS_NO_SUCCESS;
105  } // NOTE: previously checked if ID < numCameras, but turns out that ID can be arbitrary
106 
107  // Attempt to open camera handle, and handle case where camera requires a
108  // mandatory firmware upload
109  cam_handle_ = static_cast<HIDS>(cam_id_);
110  if ((is_err = is_InitCamera(&cam_handle_, nullptr)) == IS_STARTER_FW_UPLOAD_NEEDED) {
111  INT uploadTimeMSEC = 25000;
112  is_GetDuration (cam_handle_, IS_STARTER_FW_UPLOAD, &uploadTimeMSEC);
113 
114  INFO_STREAM("Uploading new firmware to [" << cam_name_
115  << "]; please wait for about " << uploadTimeMSEC/1000.0 << " seconds");
116 
117  // Attempt to re-open camera handle while triggering automatic firmware upload
118  cam_handle_ = static_cast<HIDS>(static_cast<INT>(cam_handle_) | IS_ALLOW_STARTER_FW_UPLOAD);
119  is_err = is_InitCamera(&cam_handle_, nullptr); // Will block for N seconds
120  }
121  if (is_err != IS_SUCCESS) {
122  ERROR_STREAM("Could not open UEye camera ID " << cam_id_ <<
123  " (" << err2str(is_err) << ")");
124  return is_err;
125  }
126 
127  // Set display mode to Device Independent Bitmap (DIB)
128  is_err = is_SetDisplayMode(cam_handle_, IS_SET_DM_DIB);
129  if (is_err != IS_SUCCESS) {
130  ERROR_STREAM("UEye camera ID " << cam_id_ <<
131  " does not support Device Independent Bitmap mode;" <<
132  " driver wrapper not compatible with OpenGL/DirectX modes (" << err2str(is_err) << ")");
133  return is_err;
134  }
135 
136  // Fetch sensor parameters
137  is_err = is_GetSensorInfo(cam_handle_, &cam_sensor_info_);
138  if (is_err != IS_SUCCESS) {
139  ERROR_STREAM("Could not poll sensor information for [" << cam_name_ <<
140  "] (" << err2str(is_err) << ")");
141  return is_err;
142  }
143 
144  // Validate camera's configuration to ensure compatibility with driver wrapper
145  // (note that this function also initializes the internal frame buffer)
146  if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
147 
148  DEBUG_STREAM("Connected to [" + cam_name_ + "]");
149 
150  return is_err;
151 }
152 
153 
155  INT is_err = IS_SUCCESS;
156 
157  if (isConnected()) {
158  setStandbyMode();
159 
160  // Release existing camera buffers
161  if (cam_buffer_ != nullptr) {
162  is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
163  }
164  cam_buffer_ = nullptr;
165 
166  // Release camera handle
167  is_err = is_ExitCamera(cam_handle_);
168  cam_handle_ = HIDS(0);
169 
170  DEBUG_STREAM("Disconnected from [" + cam_name_ + "]");
171  }
172 
173  return is_err;
174 }
175 
176 
177 INT UEyeCamDriver::loadCamConfig(string filename, bool ignore_load_failure) {
178  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
179 
180  INT is_err = IS_SUCCESS;
181 
182  // Convert filename to unicode, as requested by UEye API
183  const wstring filenameU(filename.begin(), filename.end());
184  if ((is_err = is_ParameterSet(cam_handle_, IS_PARAMETERSET_CMD_LOAD_FILE,
185  (void*) filenameU.c_str(), 0)) != IS_SUCCESS) {
186  WARN_STREAM("Could not load [" << cam_name_
187  << "]'s sensor parameters file " << filename << " (" << err2str(is_err) << ")");
188  if (ignore_load_failure) is_err = IS_SUCCESS;
189  return is_err;
190  } else {
191  // After loading configuration settings, need to re-ensure that camera's
192  // current configuration is supported by this driver wrapper
193  // (note that this function also initializes the internal frame buffer)
194  if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
195 
196  DEBUG_STREAM("Successfully loaded sensor parameter file for [" << cam_name_ <<
197  "]: " << filename);
198  }
199 
200  return is_err;
201 }
202 
203 
204 INT UEyeCamDriver::setColorMode(string& mode, bool reallocate_buffer) {
205  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
206 
207  INT is_err = IS_SUCCESS;
208 
209  // Stop capture to prevent access to memory buffer
210  setStandbyMode();
211 
212  // Set to specified color mode
213  color_mode_ = name2colormode(mode);
215  WARN_STREAM("Could not set color mode of [" << cam_name_
216  << "] to " << mode << " (not supported by this wrapper). "
217  << "switching to default mode: mono8");
218  color_mode_ = IS_CM_MONO8;
219  mode = "mono8";
220  }
221  if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
222  ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
223  "] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << " / '" << mode << "'). switching to default mode: mono8");
224 
225  color_mode_ = IS_CM_MONO8;
226  mode = "mono8";
227  if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
228  ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
229  "] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << "/ " << mode << ")");
230  return is_err;
231  }
232  }
234 
235  DEBUG_STREAM("Updated color mode to " << mode << "for [" << cam_name_ << "]");
236 
237  return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
238 }
239 
240 
241 INT UEyeCamDriver::setResolution(INT& image_width, INT& image_height,
242  INT& image_left, INT& image_top, bool reallocate_buffer) {
243  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
244 
245  INT is_err = IS_SUCCESS;
246 
247  // Validate arguments
248  CAP(image_width, 8, static_cast<INT>(cam_sensor_info_.nMaxWidth));
249  CAP(image_height, 4, static_cast<INT>(cam_sensor_info_.nMaxHeight));
250  if (image_left >= 0 && static_cast<int>(cam_sensor_info_.nMaxWidth) - image_width - image_left < 0) {
251  WARN_STREAM("Cannot set AOI left index to " <<
252  image_left << " with a frame width of " <<
253  image_width << " and sensor max width of " <<
254  cam_sensor_info_.nMaxWidth << " for [" << cam_name_ << "]");
255  image_left = -1;
256  }
257  if (image_top >= 0 &&
258  static_cast<int>(cam_sensor_info_.nMaxHeight) - image_height - image_top < 0) {
259  WARN_STREAM("Cannot set AOI top index to " <<
260  image_top << " with a frame height of " <<
261  image_height << " and sensor max height of " <<
262  cam_sensor_info_.nMaxHeight << " for [" << cam_name_ << "]");
263  image_top = -1;
264  }
265  cam_aoi_.s32X = (image_left < 0) ?
266  (cam_sensor_info_.nMaxWidth - static_cast<unsigned int>(image_width)) / 2 : image_left;
267  cam_aoi_.s32Y = (image_top < 0) ?
268  (cam_sensor_info_.nMaxHeight - static_cast<unsigned int>(image_height)) / 2 : image_top;
269  cam_aoi_.s32Width = image_width;
270  cam_aoi_.s32Height = image_height;
271 
273  cam_aoi_.s32X /= s;
274  cam_aoi_.s32Y /= s;
275  cam_aoi_.s32Width /= s;
276  cam_aoi_.s32Height /= s;
277 
278  if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_SET_AOI, &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
279  ERROR_STREAM("Failed to set Area Of Interest (AOI) to " <<
280  image_width << " x " << image_height <<
281  " with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
282  ") for [" << cam_name_ << "]" );
283  return is_err;
284  }
285 
286  DEBUG_STREAM("Updated Area Of Interest (AOI) to " <<
287  image_width << " x " << image_height <<
288  " with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
289  ") for [" << cam_name_ << "]");
290 
291  return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
292 }
293 
294 
295 INT UEyeCamDriver::setSubsampling(int& rate, bool reallocate_buffer) {
296  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
297 
298  INT is_err = IS_SUCCESS;
299 
300  // Stop capture to prevent access to memory buffer
301  setStandbyMode();
302 
303  INT rate_flag;
304  INT supportedRates;
305 
306  supportedRates = is_SetSubSampling(cam_handle_, IS_GET_SUPPORTED_SUBSAMPLING);
307  switch (rate) {
308  case 1:
309  rate_flag = IS_SUBSAMPLING_DISABLE;
310  break;
311  case 2:
312  rate_flag = IS_SUBSAMPLING_2X;
313  break;
314  case 4:
315  rate_flag = IS_SUBSAMPLING_4X;
316  break;
317  case 8:
318  rate_flag = IS_SUBSAMPLING_8X;
319  break;
320  case 16:
321  rate_flag = IS_SUBSAMPLING_16X;
322  break;
323  default:
324  WARN_STREAM("[" << cam_name_ << "] currently has unsupported subsampling rate: " <<
325  rate << ", resetting to 1X");
326  rate = 1;
327  rate_flag = IS_SUBSAMPLING_DISABLE;
328  break;
329  }
330 
331  if ((supportedRates & rate_flag) == rate_flag) {
332  if ((is_err = is_SetSubSampling(cam_handle_, rate_flag)) != IS_SUCCESS) {
333  ERROR_STREAM("Failed to set subsampling rate to " <<
334  rate << "X for [" << cam_name_ << "] (" << err2str(is_err) << ")");
335  return is_err;
336  }
337  } else {
338  WARN_STREAM("[" << cam_name_ << "] does not support requested sampling rate of " << rate);
339 
340  // Query current rate
341  INT currRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
342  if (currRate == IS_SUBSAMPLING_DISABLE) { rate = 1; }
343  else if (currRate == IS_SUBSAMPLING_2X) { rate = 2; }
344  else if (currRate == IS_SUBSAMPLING_4X) { rate = 4; }
345  else if (currRate == IS_SUBSAMPLING_8X) { rate = 8; }
346  else if (currRate == IS_SUBSAMPLING_16X) { rate = 16; }
347  else {
348  WARN_STREAM("[" << cam_name_ << "] currently has an unsupported sampling rate (" <<
349  currRate << "), resetting to 1X");
350  if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
351  ERROR_STREAM("Failed to set subsampling rate to 1X for [" << cam_name_ << "] (" <<
352  err2str(is_err) << ")");
353  return is_err;
354  }
355  }
356  return IS_SUCCESS;
357  }
358 
359  DEBUG_STREAM("Updated subsampling rate to " << rate << "X for [" << cam_name_ << "]");
360 
361  cam_subsampling_rate_ = static_cast<unsigned int>(rate);
362 
363  return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
364 }
365 
366 
367 INT UEyeCamDriver::setBinning(int& rate, bool reallocate_buffer) {
368  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
369 
370  INT is_err = IS_SUCCESS;
371 
372  // Stop capture to prevent access to memory buffer
373  setStandbyMode();
374 
375  INT rate_flag;
376  INT supportedRates;
377 
378  supportedRates = is_SetBinning(cam_handle_, IS_GET_SUPPORTED_BINNING);
379  switch (rate) {
380  case 1:
381  rate_flag = IS_BINNING_DISABLE;
382  break;
383  case 2:
384  rate_flag = IS_BINNING_2X;
385  break;
386  case 4:
387  rate_flag = IS_BINNING_4X;
388  break;
389  case 8:
390  rate_flag = IS_BINNING_8X;
391  break;
392  case 16:
393  rate_flag = IS_BINNING_16X;
394  break;
395  default:
396  WARN_STREAM("[" << cam_name_ << "] currently has unsupported binning rate: " <<
397  rate << ", resetting to 1X");
398  rate = 1;
399  rate_flag = IS_BINNING_DISABLE;
400  break;
401  }
402 
403  if ((supportedRates & rate_flag) == rate_flag) {
404  if ((is_err = is_SetBinning(cam_handle_, rate_flag)) != IS_SUCCESS) {
405  ERROR_STREAM("Could not set binning rate for [" << cam_name_ << "] to " <<
406  rate << "X (" << err2str(is_err) << ")");
407  return is_err;
408  }
409  } else {
410  WARN_STREAM("[" << cam_name_ << "] does not support requested binning rate of " << rate);
411 
412  // Query current rate
413  INT currRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
414  if (currRate == IS_BINNING_DISABLE) { rate = 1; }
415  else if (currRate == IS_BINNING_2X) { rate = 2; }
416  else if (currRate == IS_BINNING_4X) { rate = 4; }
417  else if (currRate == IS_BINNING_8X) { rate = 8; }
418  else if (currRate == IS_BINNING_16X) { rate = 16; }
419  else {
420  WARN_STREAM("[" << cam_name_ << "] currently has an unsupported binning rate (" <<
421  currRate << "), resetting to 1X");
422  if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
423  ERROR_STREAM("Failed to set binning rate for [" << cam_name_ << "] to 1X (" <<
424  err2str(is_err) << ")");
425  return is_err;
426  }
427  }
428  return IS_SUCCESS;
429  }
430 
431  DEBUG_STREAM("Updated binning rate to " << rate << "X for [" << cam_name_ << "]");
432 
433  cam_binning_rate_ = static_cast<unsigned int>(rate);
434 
435  return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
436 }
437 
438 
439 INT UEyeCamDriver::setSensorScaling(double& rate, bool reallocate_buffer) {
440  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
441 
442  INT is_err = IS_SUCCESS;
443 
444  // Stop capture to prevent access to memory buffer
445  setStandbyMode();
446 
447  SENSORSCALERINFO sensorScalerInfo;
448  is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
449  if (is_err == IS_NOT_SUPPORTED) {
450  WARN_STREAM("[" << cam_name_ << "] does not support internal image scaling");
451  rate = 1.0;
453  return IS_SUCCESS;
454  } else if (is_err != IS_SUCCESS) {
455  ERROR_STREAM("Failed to obtain supported internal image scaling information for [" <<
456  cam_name_ << "] (" << err2str(is_err) << ")");
457  rate = 1.0;
459  return is_err;
460  } else {
461  if (rate < sensorScalerInfo.dblMinFactor || rate > sensorScalerInfo.dblMaxFactor) {
462  WARN_STREAM("Requested internal image scaling rate of " << rate <<
463  " is not within supported bounds for [" << cam_name_ << "]: " <<
464  sensorScalerInfo.dblMinFactor << ", " << sensorScalerInfo.dblMaxFactor <<
465  "; not updating current rate of " << sensorScalerInfo.dblCurrFactor);
466  rate = sensorScalerInfo.dblCurrFactor;
467  return IS_SUCCESS;
468  }
469  }
470 
471  if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
472  WARN_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
473  "] to " << rate << "X (" << err2str(is_err) << "); resetting to 1X");
474  rate = 1.0;
475  if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
476  ERROR_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
477  "] to 1X (" << err2str(is_err) << ")");
478  return is_err;
479  }
480  }
481 
482  DEBUG_STREAM("Updated internal image scaling rate to " << rate << "X for [" << cam_name_ << "]");
483 
485 
486  return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
487 }
488 
489 
490 INT UEyeCamDriver::setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
491  INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost) {
492  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
493 
494  INT is_err = IS_SUCCESS;
495 
496  // Validate arguments
497  CAP(master_gain_prc, 0, 100);
498  CAP(red_gain_prc, 0, 100);
499  CAP(green_gain_prc, 0, 100);
500  CAP(blue_gain_prc, 0, 100);
501 
502  double pval1 = 0, pval2 = 0;
503 
504  if (auto_gain) {
505  // Set auto gain
506  pval1 = 1;
507  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
508  &pval1, &pval2)) != IS_SUCCESS) {
509  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
510  &pval1, &pval2)) != IS_SUCCESS) {
511  WARN_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
512  auto_gain = false;
513  }
514  }
515  } else {
516  // Disable auto gain
517  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
518  &pval1, &pval2)) != IS_SUCCESS) {
519  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
520  &pval1, &pval2)) != IS_SUCCESS) {
521  DEBUG_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
522  }
523  }
524 
525  // Set gain boost
526  if (is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
527  gain_boost = false;
528  } else {
529  if ((is_err = is_SetGainBoost(cam_handle_,
530  (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF))
531  != IS_SUCCESS) {
532  WARN_STREAM("Failed to " << ((gain_boost) ? "enable" : "disable") <<
533  " gain boost for [" << cam_name_ << "] (" << err2str(is_err) << ")");
534  }
535  }
536 
537  // Set manual gain parameters
538  if ((is_err = is_SetHardwareGain(cam_handle_, master_gain_prc,
539  red_gain_prc, green_gain_prc, blue_gain_prc)) != IS_SUCCESS) {
540  WARN_STREAM("Failed to set manual gains (master: " << master_gain_prc <<
541  "; red: " << red_gain_prc << "; green: " << green_gain_prc <<
542  "; blue: " << blue_gain_prc << ") for [" << cam_name_ << "] (" <<
543  err2str(is_err) << ")");
544  }
545  }
546 
547  if (auto_gain) {
548  DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: auto");
549  } else {
550  DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: manual" <<
551  "\n master gain: " << master_gain_prc <<
552  "\n red gain: " << red_gain_prc <<
553  "\n green gain: " << green_gain_prc <<
554  "\n blue gain: " << blue_gain_prc <<
555  "\n gain boost: " << gain_boost);
556  }
557 
558  return is_err;
559 }
560 
561 
562 INT UEyeCamDriver::setSoftwareGamma(INT& software_gamma) {
563  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
564 
565  INT is_err = IS_SUCCESS;
566 
567  // According to ids this is only possible when the color mode is debayered by the ids driver
568  if ((color_mode_ == IS_CM_SENSOR_RAW8) ||
569  (color_mode_ == IS_CM_SENSOR_RAW10) ||
570  (color_mode_ == IS_CM_SENSOR_RAW12) ||
571  (color_mode_ == IS_CM_SENSOR_RAW16)) {
572  WARN_STREAM("Software gamma only possible when the color mode is debayered, " <<
573  "could not set software gamma for [" << cam_name_ << "]");
574  return IS_NO_SUCCESS;
575  }
576 
577  // set software gamma
578  if ((is_err = is_Gamma(cam_handle_, IS_GAMMA_CMD_SET, (void*) &software_gamma, sizeof(software_gamma))) != IS_SUCCESS) {
579  WARN_STREAM("Software gamma could not be set for [" << cam_name_ <<
580  "] (" << err2str(is_err) << ")");
581  }
582 
583  return is_err;
584 }
585 
586 
587 INT UEyeCamDriver::setExposure(bool& auto_exposure, double& auto_exposure_reference, double& exposure_ms) {
588  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
589 
590  INT is_err = IS_SUCCESS;
591 
592  double minExposure, maxExposure;
593 
594  // Set auto exposure
595  double pval1 = auto_exposure, pval2 = 0;
596  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER,
597  &pval1, &pval2)) != IS_SUCCESS) {
598  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SHUTTER,
599  &pval1, &pval2)) != IS_SUCCESS) {
600  WARN_STREAM("Auto exposure mode is not supported for [" << cam_name_ <<
601  "] (" << err2str(is_err) << ")");
602  auto_exposure = false;
603  }
604  }
605 
606  // Set exposure reference for auto exposure controller
607  if ((is_err = is_SetAutoParameter (cam_handle_, IS_SET_AUTO_REFERENCE,
608  &auto_exposure_reference, 0)) != IS_SUCCESS) {
609  WARN_STREAM("Auto exposure reference value could not be set for [" << cam_name_ <<
610  "] (" << err2str(is_err) << ")");
611  }
612 
613  // Set manual exposure timing
614  if (!auto_exposure) {
615  // Make sure that user-requested exposure rate is achievable
616  if (((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN,
617  (void*) &minExposure, sizeof(minExposure))) != IS_SUCCESS) ||
618  ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX,
619  (void*) &maxExposure, sizeof(maxExposure))) != IS_SUCCESS)) {
620  ERROR_STREAM("Failed to query valid exposure range from [" << cam_name_ << "]");
621  return is_err;
622  }
623  CAP(exposure_ms, minExposure, maxExposure);
624 
625  // Update exposure
626  if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_SET_EXPOSURE,
627  (void*) &(exposure_ms), sizeof(exposure_ms))) != IS_SUCCESS) {
628  ERROR_STREAM("Failed to set exposure to " << exposure_ms <<
629  " ms for [" << cam_name_ << "]");
630  return is_err;
631  }
632  }
633 
634  DEBUG_STREAM("Updated exposure: " << ((auto_exposure) ? "auto" : to_string(exposure_ms)) <<
635  " ms for [" << cam_name_ << "]");
636 
637  return is_err;
638 }
639 
640 
641 INT UEyeCamDriver::setWhiteBalance(bool& auto_white_balance, INT& red_offset,
642  INT& blue_offset) {
643  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
644 
645  INT is_err = IS_SUCCESS;
646 
647  CAP(red_offset, -50, 50);
648  CAP(blue_offset, -50, 50);
649 
650  // Set auto white balance mode and parameters
651  double pval1 = auto_white_balance, pval2 = 0;
652  // TODO: 9 bug: enabling auto white balance does not seem to have an effect; in ueyedemo it seems to change R/G/B gains automatically
653  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_WHITEBALANCE,
654  &pval1, &pval2)) != IS_SUCCESS) {
655  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_ONCE,
656  &pval1, &pval2)) != IS_SUCCESS) {
657  WARN_STREAM("Auto white balance mode is not supported for [" << cam_name_ <<
658  "] (" << err2str(is_err) << ")");
659  auto_white_balance = false;
660  }
661  }
662  if (auto_white_balance) {
663  pval1 = red_offset;
664  pval2 = blue_offset;
665  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_OFFSET,
666  &pval1, &pval2)) != IS_SUCCESS) {
667  WARN_STREAM("Failed to set white balance red/blue offsets to " <<
668  red_offset << " / " << blue_offset <<
669  " for [" << cam_name_ << "] (" << err2str(is_err) << ")");
670  }
671  }
672 
673  DEBUG_STREAM("Updated white balance for [" << cam_name_ << "]: " <<
674  ((auto_white_balance) ? "auto" : "manual") <<
675  "\n red offset: " << red_offset <<
676  "\n blue offset: " << blue_offset);
677 
678  return is_err;
679 }
680 
681 
682 INT UEyeCamDriver::setFrameRate(bool& auto_frame_rate, double& frame_rate_hz) {
683  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
684 
685  INT is_err = IS_SUCCESS;
686 
687  double pval1 = 0, pval2 = 0;
688  double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
689 
690  // Make sure that auto shutter is enabled before enabling auto frame rate
691  bool autoShutterOn = false;
692  is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
693  autoShutterOn |= (pval1 != 0);
694  is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
695  autoShutterOn |= (pval1 != 0);
696  if (!autoShutterOn) {
697  auto_frame_rate = false;
698  }
699 
700  // Set frame rate / auto
701  pval1 = auto_frame_rate;
702  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE,
703  &pval1, &pval2)) != IS_SUCCESS) {
704  if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_FRAMERATE,
705  &pval1, &pval2)) != IS_SUCCESS) {
706  WARN_STREAM("Auto frame rate mode is not supported for [" << cam_name_ <<
707  "] (" << err2str(is_err) << ")");
708  auto_frame_rate = false;
709  }
710  }
711  if (!auto_frame_rate) {
712  // Make sure that user-requested frame rate is achievable
713  if ((is_err = is_GetFrameTimeRange(cam_handle_, &minFrameTime,
714  &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
715  ERROR_STREAM("Failed to query valid frame rate range from [" << cam_name_ <<
716  "] (" << err2str(is_err) << ")");
717  return is_err;
718  }
719  CAP(frame_rate_hz, 1.0/maxFrameTime, 1.0/minFrameTime);
720 
721  // Update frame rate
722  if ((is_err = is_SetFrameRate(cam_handle_, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
723  ERROR_STREAM("Failed to set frame rate to " << frame_rate_hz <<
724  " MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
725  return is_err;
726  } else if (frame_rate_hz != newFrameRate) {
727  frame_rate_hz = newFrameRate;
728  }
729  }
730 
731  DEBUG_STREAM("Updated frame rate for [" << cam_name_ << "]: " <<
732  ((auto_frame_rate) ? "auto" : to_string(frame_rate_hz)) << " Hz");
733 
734  return is_err;
735 }
736 
737 
738 INT UEyeCamDriver::setPixelClockRate(INT& clock_rate_mhz) {
739  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
740 
741  INT is_err = IS_SUCCESS;
742 
743  UINT pixelClockList[150]; // No camera has more than 150 different pixel clocks (uEye manual)
744  UINT numberOfSupportedPixelClocks = 0;
745  if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_NUMBER,
746  (void*) &numberOfSupportedPixelClocks, sizeof(numberOfSupportedPixelClocks))) != IS_SUCCESS) {
747  ERROR_STREAM("Failed to query number of supported pixel clocks from [" << cam_name_ <<
748  "] (" << err2str(is_err) << ")");
749  return is_err;
750  }
751  if(numberOfSupportedPixelClocks > 0) {
752  ZeroMemory(pixelClockList, sizeof(pixelClockList));
753  if((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_LIST,
754  (void*) pixelClockList, numberOfSupportedPixelClocks * sizeof(int))) != IS_SUCCESS) {
755  ERROR_STREAM("Failed to query list of supported pixel clocks from [" << cam_name_ <<
756  "] (" << err2str(is_err) << ")");
757  return is_err;
758  }
759  }
760  int minPixelClock = static_cast<int>(pixelClockList[0]);
761  int maxPixelClock = static_cast<int>(pixelClockList[numberOfSupportedPixelClocks-1]);
762  CAP(clock_rate_mhz, minPixelClock, maxPixelClock);
763 
764  // As list is sorted smallest to largest...
765  for(UINT i = 0; i < numberOfSupportedPixelClocks; i++) {
766  if(clock_rate_mhz <= static_cast<int>(pixelClockList[i])) {
767  clock_rate_mhz = static_cast<INT>(pixelClockList[i]); // ...get the closest-larger-or-equal from the list
768  break;
769  }
770  }
771 
772  if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_SET,
773  (void*) &(clock_rate_mhz), sizeof(clock_rate_mhz))) != IS_SUCCESS) {
774  ERROR_STREAM("Failed to set pixel clock to " << clock_rate_mhz <<
775  "MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
776  return is_err;
777  }
778 
779  DEBUG_STREAM("Updated pixel clock for [" << cam_name_ << "]: " << clock_rate_mhz << " MHz");
780 
781  return IS_SUCCESS;
782 }
783 
784 
785 INT UEyeCamDriver::setFlashParams(INT& delay_us, UINT& duration_us) {
786  INT is_err = IS_SUCCESS;
787 
788  // Make sure parameters are within range supported by camera
789  IO_FLASH_PARAMS minFlashParams, maxFlashParams, newFlashParams;
790  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MIN,
791  (void*) &minFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
792  ERROR_STREAM("Failed to retrieve flash parameter info (min) for [" << cam_name_ <<
793  "] (" << err2str(is_err) << ")");
794  return is_err;
795  }
796  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MAX,
797  (void*) &maxFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
798  ERROR_STREAM("Failed to retrieve flash parameter info (max) for [" << cam_name_ <<
799  "] (" << err2str(is_err) << ")");
800  return is_err;
801  }
802  delay_us = (delay_us < minFlashParams.s32Delay) ? minFlashParams.s32Delay :
803  ((delay_us > maxFlashParams.s32Delay) ? maxFlashParams.s32Delay : delay_us);
804  duration_us = (duration_us < minFlashParams.u32Duration && duration_us != 0) ? minFlashParams.u32Duration :
805  ((duration_us > maxFlashParams.u32Duration) ? maxFlashParams.u32Duration : duration_us);
806  newFlashParams.s32Delay = delay_us;
807  newFlashParams.u32Duration = duration_us;
808  // WARNING: Setting s32Duration to 0, according to documentation, means
809  // setting duration to total exposure time. If non-ext-triggered
810  // camera is operating at fastest grab rate, then the resulting
811  // flash signal will APPEAR as active LO when set to active HIGH,
812  // and vice versa. This is why the duration is set manually.
813  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_PARAMS,
814  (void*) &newFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
815  WARN_STREAM("Failed to set flash parameter info for [" << cam_name_ <<
816  "] (" << err2str(is_err) << ")");
817  return is_err;
818  }
819 
820  return is_err;
821 }
822 
823 
824 INT UEyeCamDriver::setGpioMode(const int& gpio, int& mode, double& pwm_freq, double& pwm_duty_cycle) {
825  /* Set GPIO to a specific mode. */
826  INT is_err = IS_SUCCESS;
827  IO_GPIO_CONFIGURATION gpioConfiguration;
828  gpioConfiguration.u32State = 0;
829  IO_PWM_PARAMS m_pwmParams;
830 
831  if (gpio == 1)
832  gpioConfiguration.u32Gpio = IO_GPIO_1; // GPIO1 (pin 5).
833  else if (gpio == 2)
834  gpioConfiguration.u32Gpio = IO_GPIO_2; // GPIO2 (pin 6).
835 
836  switch (mode) {
837  case 0: gpioConfiguration.u32Configuration = IS_GPIO_INPUT; break;
838  case 1: gpioConfiguration.u32Configuration = IS_GPIO_OUTPUT; break;
839  case 2:
840  gpioConfiguration.u32Configuration = IS_GPIO_OUTPUT;
841  gpioConfiguration.u32State = 1;
842  break;
843  case 3: gpioConfiguration.u32Configuration = IS_GPIO_FLASH; break;
844  case 4:
845  gpioConfiguration.u32Configuration = IS_GPIO_PWM;
846  m_pwmParams.dblFrequency_Hz = pwm_freq;
847  m_pwmParams.dblDutyCycle = pwm_duty_cycle;
848  break;
849  case 5: gpioConfiguration.u32Configuration = IS_GPIO_TRIGGER; break;
850  }
851 
852  // set GPIO regarding the selected pind and mode
853  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_GPIOS_SET_CONFIGURATION, (void*)&gpioConfiguration, sizeof(gpioConfiguration))) != IS_SUCCESS) {
854  ERROR_STREAM("Tried to set GPIO: " << gpioConfiguration.u32Gpio << " and got error code: " << is_err);
855  }
856 
857  // Set PWM details if prior change of GPIO was successfull and mode is PWM
858  if ((is_err == IS_SUCCESS) && (mode == 4)) {
859  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_PWM_SET_PARAMS, (void*)&m_pwmParams, sizeof(m_pwmParams))) != IS_SUCCESS) {
860  ERROR_STREAM("Tried to set PWM to: " << m_pwmParams.dblFrequency_Hz << " hz and " << m_pwmParams.dblDutyCycle <<
861  " % and got error code: " << is_err);
862  }
863  }
864 
865  return is_err;
866 }
867 
868 
870  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
871 
872  INT is_err = IS_SUCCESS;
873 
874  if (!freeRunModeActive()) {
875  setStandbyMode(); // No need to check for success
876 
877  // Set the flash to a high active pulse for each image in the trigger mode
878  INT flash_delay = 0;
879  UINT flash_duration = 1000;
880  setFlashParams(flash_delay, flash_duration);
881  UINT nMode = IO_FLASH_MODE_FREERUN_HI_ACTIVE;
882  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
883  (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
884  WARN_STREAM("Could not set free-run active-low flash output for [" << cam_name_ <<
885  "] (" << err2str(is_err) << ")");
886  WARN_STREAM("WARNING: camera hardware does not support ueye_cam's master-slave synchronization method");
887  }
888  IS_INIT_EVENT init_events[] = {{IS_SET_EVENT_FRAME, FALSE, FALSE}};
889  if ((is_err = is_Event(cam_handle_, IS_EVENT_CMD_INIT, init_events, sizeof(init_events))) != IS_SUCCESS) {
890  ERROR_STREAM("Could not init frame event for [" << cam_name_ <<
891  "] (" << err2str(is_err) << ")");
892  return is_err;
893  }
894  UINT events[] = {IS_SET_EVENT_FRAME};
895  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_ENABLE, events, sizeof(events))) != IS_SUCCESS) {
896  ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
897  "] (" << err2str(is_err) << ")");
898  return is_err;
899  }
900  if ((is_err = is_CaptureVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
901  ERROR_STREAM("Could not start free-run live video mode for [" << cam_name_ <<
902  "] (" << err2str(is_err) << ")");
903  return is_err;
904  }
905  DEBUG_STREAM("Started live video mode for [" << cam_name_ << "]");
906  }
907 
908  return is_err;
909 }
910 
911 
913  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
914 
915  INT is_err = IS_SUCCESS;
916 
917  if (!extTriggerModeActive()) {
918  setStandbyMode(); // No need to check for success
919 
920  IS_INIT_EVENT init_events[] = {{IS_SET_EVENT_FRAME, FALSE, FALSE}};
921  if ((is_err = is_Event(cam_handle_, IS_EVENT_CMD_INIT, init_events, sizeof(init_events))) != IS_SUCCESS) {
922  ERROR_STREAM("Could not init frame event for [" << cam_name_ <<
923  "] (" << err2str(is_err) << ")");
924  return is_err;
925  }
926  UINT events[] = {IS_SET_EVENT_FRAME};
927  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_ENABLE, events, sizeof(events))) != IS_SUCCESS) {
928  ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
929  "] (" << err2str(is_err) << ")");
930  return is_err;
931  }
932 
933  if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_HI_LO)) != IS_SUCCESS) {
934  ERROR_STREAM("Could not enable falling-edge external trigger mode for [" <<
935  cam_name_ << "] (" << err2str(is_err) << ")");
936  return is_err;
937  }
938  if ((is_err = is_CaptureVideo(cam_handle_, IS_DONT_WAIT)) != IS_SUCCESS) {
939  ERROR_STREAM("Could not start external trigger live video mode for [" <<
940  cam_name_ << "] (" << err2str(is_err) << ")");
941  return is_err;
942  }
943  DEBUG_STREAM("Started falling-edge external trigger live video mode for [" <<
944  cam_name_ << "]");
945  }
946 
947  return is_err;
948 }
949 
950 
951 INT UEyeCamDriver::setMirrorUpsideDown(bool flip_horizontal){
952  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
953 
954  INT is_err = IS_SUCCESS;
955  if(flip_horizontal)
956  is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,1,0);
957  else
958  is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,0,0);
959 
960  return is_err;
961 }
962 
963 
964 INT UEyeCamDriver::setMirrorLeftRight(bool flip_vertical){
965  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
966 
967  INT is_err = IS_SUCCESS;
968  if(flip_vertical)
969  is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,1,0);
970  else
971  is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,0,0);
972 
973  return is_err;
974 }
975 
976 
978  if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
979 
980  INT is_err = IS_SUCCESS;
981 
982  UINT events[] = {IS_SET_EVENT_FRAME};
983 
984  if (extTriggerModeActive()) {
985  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_DISABLE, events, sizeof(events))) != IS_SUCCESS) {
986  ERROR_STREAM("Could not disable frame event for [" << cam_name_ <<
987  "] (" << err2str(is_err) << ")");
988  return is_err;
989  }
990  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_EXIT, events, sizeof(events))) != IS_SUCCESS) {
991  ERROR_STREAM("Could not exit frame event for [" << cam_name_ <<
992  "] (" << err2str(is_err) << ")");
993  return is_err;
994  }
995  if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_OFF)) != IS_SUCCESS) {
996  ERROR_STREAM("Could not disable external trigger mode for [" << cam_name_ <<
997  "] (" << err2str(is_err) << ")");
998  return is_err;
999  }
1000  is_SetExternalTrigger(cam_handle_, IS_GET_TRIGGER_STATUS); // documentation seems to suggest that this is needed to disable external trigger mode (to go into free-run mode)
1001  if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
1002  ERROR_STREAM("Could not stop live video mode for [" << cam_name_ <<
1003  "] (" << err2str(is_err) << ")");
1004  return is_err;
1005  }
1006  DEBUG_STREAM("Stopped external trigger mode for [" << cam_name_ << "]");
1007  } else if (freeRunModeActive()) {
1008  UINT nMode = IO_FLASH_MODE_OFF;
1009  if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
1010  (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
1011  ERROR_STREAM("Could not disable flash output for [" << cam_name_ <<
1012  "] (" << err2str(is_err) << ")");
1013  return is_err;
1014  }
1015  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_DISABLE, events, sizeof(events))) != IS_SUCCESS) {
1016  ERROR_STREAM("Could not disable frame event for [" << cam_name_ <<
1017  "] (" << err2str(is_err) << ")");
1018  return is_err;
1019  }
1020  if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_EXIT, events, sizeof(events))) != IS_SUCCESS) {
1021  ERROR_STREAM("Could not exit frame event for [" << cam_name_ <<
1022  "] (" << err2str(is_err) << ")");
1023  return is_err;
1024  }
1025  if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
1026  ERROR_STREAM("Could not stop live video mode for [" << cam_name_ <<
1027  "] (" << err2str(is_err) << ")");
1028  return is_err;
1029  }
1030  DEBUG_STREAM("Stopped free-run live video mode for [" << cam_name_ << "]");
1031  }
1032  if ((is_err = static_cast<int>(is_CameraStatus(cam_handle_, IS_STANDBY, IS_GET_STATUS))) != IS_SUCCESS) {
1033  ERROR_STREAM("Could not set standby mode for [" << cam_name_ <<
1034  "] (" << err2str(is_err) << ")");
1035  return is_err;
1036  }
1037 
1038  return is_err;
1039 }
1040 
1041 
1042 const char* UEyeCamDriver::processNextFrame(UINT timeout_ms) {
1043  if (!freeRunModeActive() && !extTriggerModeActive()) return nullptr;
1044 
1045  INT is_err = IS_SUCCESS;
1046 
1047  // Wait for frame event
1048  UINT events[] = {IS_SET_EVENT_FRAME};
1049  IS_WAIT_EVENTS wait_events = {events, 1, FALSE, timeout_ms, 0, 0};
1050  if ((is_err = is_Event(cam_handle_, IS_EVENT_CMD_WAIT, &wait_events, sizeof(wait_events))) != IS_SUCCESS) {
1051  if (is_err == IS_TIMED_OUT) {
1052  ERROR_STREAM("Timed out while acquiring image from [" << cam_name_ <<
1053  "] (" << err2str(is_err) << ")");
1054  ERROR_STREAM("If this is occurring frequently, see https://github.com/anqixu/ueye_cam/issues/6#issuecomment-49925549");
1055  handleTimeout();
1056  } else {
1057  ERROR_STREAM("Failed to acquire image from [" << cam_name_ <<
1058  "] (" << err2str(is_err) << ")");
1059  }
1060  return nullptr;
1061  }
1062 
1063  return cam_buffer_;
1064 }
1065 
1066 
1067 INT UEyeCamDriver::syncCamConfig(string dft_mode_str) {
1068  INT is_err = IS_SUCCESS;
1069 
1070  // Synchronize resolution, color mode, bits per pixel settings
1071  if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_GET_AOI,
1072  (void*) &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
1073  ERROR_STREAM("Could not retrieve Area Of Interest (AOI) information from [" <<
1074  cam_name_ << "] (" << err2str(is_err) << ")");
1075  return is_err;
1076  }
1077  color_mode_ = is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE);
1079  WARN_STREAM("Current color mode (IDS format: " << colormode2str(color_mode_)
1080  << ") for [" << cam_name_ << "] is not supported by this wrapper; "
1081  //<< "supported modes: {mono8 | mono10 | mono12 | mono16 | bayer_rggb8 | rgb8 | bgr8 | rgb10 | bgr10 | rgb10u | bgr10u | rgb12u | bgr12u}; "
1082  << "switching to default mode: " << dft_mode_str);
1083  if ((is_err = setColorMode(dft_mode_str, false)) != IS_SUCCESS) return is_err;
1084  // reallocate_buffer == false, since this fn will force-re-allocate anyways
1085  }
1087 
1088  // Synchronize sensor scaling rate setting
1089  SENSORSCALERINFO sensorScalerInfo;
1090  is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
1091  if (is_err == IS_NOT_SUPPORTED) {
1093  } else if (is_err != IS_SUCCESS) {
1094  ERROR_STREAM("Could not obtain supported internal image scaling information for [" <<
1095  cam_name_ << "] (" << err2str(is_err) << ")");
1096  return is_err;
1097  } else {
1098  cam_sensor_scaling_rate_ = sensorScalerInfo.dblCurrFactor;
1099  }
1100 
1101  // Synchronize subsampling rate setting
1102  const INT currSubsamplingRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
1103  switch (currSubsamplingRate) {
1104  case (IS_SUBSAMPLING_DISABLE): cam_subsampling_rate_ = 1; break;
1105  case (IS_SUBSAMPLING_2X): cam_subsampling_rate_ = 2; break;
1106  case (IS_SUBSAMPLING_4X): cam_subsampling_rate_ = 4; break;
1107  case (IS_SUBSAMPLING_8X): cam_subsampling_rate_ = 8; break;
1108  case (IS_SUBSAMPLING_16X): cam_subsampling_rate_ = 16; break;
1109  default:
1110  WARN_STREAM("Current sampling rate (IDS setting: " << currSubsamplingRate
1111  << ") for [" << cam_name_ << "] is not supported by this wrapper; resetting to 1X");
1112  if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
1113  ERROR_STREAM("Could not set subsampling rate for [" << cam_name_
1114  << "] to 1X (" << err2str(is_err) << ")");
1115  return is_err;
1116  }
1117  cam_subsampling_rate_ = 1; break;
1118  }
1119 
1120  // Synchronize binning rate setting
1121  const INT currBinningRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
1122  switch (currBinningRate) {
1123  case (IS_BINNING_DISABLE): cam_binning_rate_ = 1; break;
1124  case (IS_BINNING_2X): cam_binning_rate_ = 2; break;
1125  case (IS_BINNING_4X): cam_binning_rate_ = 4; break;
1126  case (IS_BINNING_8X): cam_binning_rate_ = 8; break;
1127  case (IS_BINNING_16X): cam_binning_rate_ = 16; break;
1128  default:
1129  WARN_STREAM("Current binning rate (IDS setting: " << currBinningRate
1130  << ") for [" << cam_name_ << "] is not supported by this wrapper; resetting to 1X");
1131  if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
1132  ERROR_STREAM("Could not set binning rate for [" << cam_name_
1133  << "] to 1X (" << err2str(is_err) << ")");
1134  return is_err;
1135  }
1136  cam_binning_rate_ = 1; break;
1137  }
1138 
1139  // Report synchronized settings
1140  DEBUG_STREAM("Synchronized configuration of [" << cam_name_ <<
1141  "] and ensured compatibility with driver wrapper:" <<
1142  "\n AOI width: " << cam_aoi_.s32Width <<
1143  "\n AOI height: " << cam_aoi_.s32Height <<
1144  "\n AOI top-left X: " << cam_aoi_.s32X <<
1145  "\n AOI top-left Y: " << cam_aoi_.s32Y <<
1146  "\n IDS color mode: " << colormode2str(color_mode_) <<
1147  "\n bits per pixel: " << bits_per_pixel_ <<
1148  "\n sensor scaling rate: " << cam_sensor_scaling_rate_ <<
1149  "\n subsampling rate: " << cam_subsampling_rate_ <<
1150  "\n binning rate: " << cam_binning_rate_);
1151 
1152  // Force (re-)allocate internal frame buffer
1153  return reallocateCamBuffer();
1154 }
1155 
1156 
1158  INT is_err = IS_SUCCESS;
1159 
1160  // Stop capture to prevent access to memory buffer
1161  setStandbyMode();
1162 
1163  // Free existing memory from previous calls to reallocateCamBuffer()
1164  if (cam_buffer_ != nullptr) {
1165  is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
1166  cam_buffer_ = nullptr;
1167  }
1168 
1169  // Query camera's current resolution settings, for redundancy
1170  if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_GET_AOI,
1171  (void*) &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
1172  ERROR_STREAM("Could not retrieve Area Of Interest (AOI) information for [" <<
1173  cam_name_ << "] (" << err2str(is_err) << ")");
1174  return is_err;
1175  }
1176 
1177  // Allocate new memory section for IDS driver to use as frame buffer
1178  if ((is_err = is_AllocImageMem(cam_handle_, cam_aoi_.s32Width, cam_aoi_.s32Height,
1179  bits_per_pixel_, &cam_buffer_, &cam_buffer_id_)) != IS_SUCCESS) {
1180  ERROR_STREAM("Failed to allocate " << cam_aoi_.s32Width << " x " << cam_aoi_.s32Height <<
1181  " image buffer for [" << cam_name_ << "]");
1182  return is_err;
1183  }
1184 
1185  // Tell IDS driver to use allocated memory section as frame buffer
1186  if ((is_err = is_SetImageMem(cam_handle_, cam_buffer_, cam_buffer_id_)) != IS_SUCCESS) {
1187  ERROR_STREAM("Failed to associate image buffer to IDS driver for [" <<
1188  cam_name_ << "] (" << err2str(is_err) << ")");
1189  return is_err;
1190  }
1191 
1192  // Synchronize internal settings for buffer step size and overall buffer size
1193  // NOTE: assume that sensor_scaling_rate, subsampling_rate, and cam_binning_rate_
1194  // have all been previously validated and synchronized by syncCamConfig()
1195  if ((is_err = is_GetImageMemPitch(cam_handle_, &cam_buffer_pitch_)) != IS_SUCCESS) {
1196  ERROR_STREAM("Failed to query buffer step size / pitch / stride for [" <<
1197  cam_name_ << "] (" << err2str(is_err) << ")");
1198  return is_err;
1199  }
1200  if (cam_buffer_pitch_ < cam_aoi_.s32Width * bits_per_pixel_/8) {
1201  ERROR_STREAM("Frame buffer's queried step size (" << cam_buffer_pitch_ <<
1202  ") is smaller than buffer's expected stride [= width (" << cam_aoi_.s32Width << ") * bits per pixel (" << bits_per_pixel_ << ") /8] for [" << cam_name_ <<
1203  "]\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
1204  }
1205  cam_buffer_size_ = static_cast<unsigned int>(cam_buffer_pitch_ * cam_aoi_.s32Height);
1206 
1207  // Report updated settings
1208  DEBUG_STREAM("Allocated internal memory for [" << cam_name_ << "]:" <<
1209  "\n buffer width: " << cam_aoi_.s32Width <<
1210  "\n buffer height: " << cam_aoi_.s32Height <<
1211  "\n buffer step/pitch/stride: " << cam_buffer_pitch_ <<
1212  "\n expected bits per pixel: " << bits_per_pixel_ <<
1213  "\n expected buffer size: " << cam_buffer_size_);
1214 
1215  return is_err;
1216 }
1217 
1218 
1219 const char* UEyeCamDriver::err2str(INT error) {
1220 #define CASE(s) case s: return #s; break
1221  switch (error) {
1222  CASE(IS_NO_SUCCESS);
1223  CASE(IS_SUCCESS);
1224  CASE(IS_INVALID_CAMERA_HANDLE);
1225  CASE(IS_IO_REQUEST_FAILED);
1226  CASE(IS_CANT_OPEN_DEVICE);
1227  CASE(IS_CANT_OPEN_REGISTRY);
1228  CASE(IS_CANT_READ_REGISTRY);
1229  CASE(IS_NO_IMAGE_MEM_ALLOCATED);
1230  CASE(IS_CANT_CLEANUP_MEMORY);
1231  CASE(IS_CANT_COMMUNICATE_WITH_DRIVER);
1232  CASE(IS_FUNCTION_NOT_SUPPORTED_YET);
1233  CASE(IS_INVALID_CAPTURE_MODE);
1234  CASE(IS_INVALID_MEMORY_POINTER);
1235  CASE(IS_FILE_WRITE_OPEN_ERROR);
1236  CASE(IS_FILE_READ_OPEN_ERROR);
1237  CASE(IS_FILE_READ_INVALID_BMP_ID);
1238  CASE(IS_FILE_READ_INVALID_BMP_SIZE);
1239  CASE(IS_NO_ACTIVE_IMG_MEM);
1240  CASE(IS_SEQUENCE_LIST_EMPTY);
1241  CASE(IS_CANT_ADD_TO_SEQUENCE);
1242  CASE(IS_SEQUENCE_BUF_ALREADY_LOCKED);
1243  CASE(IS_INVALID_DEVICE_ID);
1244  CASE(IS_INVALID_BOARD_ID);
1245  CASE(IS_ALL_DEVICES_BUSY);
1246  CASE(IS_TIMED_OUT);
1247  CASE(IS_NULL_POINTER);
1248  CASE(IS_INVALID_PARAMETER);
1249  CASE(IS_OUT_OF_MEMORY);
1250  CASE(IS_ACCESS_VIOLATION);
1251  CASE(IS_NO_USB20);
1252  CASE(IS_CAPTURE_RUNNING);
1253  CASE(IS_IMAGE_NOT_PRESENT);
1254  CASE(IS_TRIGGER_ACTIVATED);
1255  CASE(IS_CRC_ERROR);
1256  CASE(IS_NOT_YET_RELEASED);
1257  CASE(IS_WAITING_FOR_KERNEL);
1258  CASE(IS_NOT_SUPPORTED);
1259  CASE(IS_TRIGGER_NOT_ACTIVATED);
1260  CASE(IS_OPERATION_ABORTED);
1261  CASE(IS_BAD_STRUCTURE_SIZE);
1262  CASE(IS_INVALID_BUFFER_SIZE);
1263  CASE(IS_INVALID_PIXEL_CLOCK);
1264  CASE(IS_INVALID_EXPOSURE_TIME);
1265  CASE(IS_AUTO_EXPOSURE_RUNNING);
1266  CASE(IS_CANNOT_CREATE_BB_SURF);
1267  CASE(IS_CANNOT_CREATE_BB_MIX);
1268  CASE(IS_BB_OVLMEM_NULL);
1269  CASE(IS_CANNOT_CREATE_BB_OVL);
1270  CASE(IS_NOT_SUPP_IN_OVL_SURF_MODE);
1271  CASE(IS_INVALID_SURFACE);
1272  CASE(IS_SURFACE_LOST);
1273  CASE(IS_RELEASE_BB_OVL_DC);
1274  CASE(IS_BB_TIMER_NOT_CREATED);
1275  CASE(IS_BB_OVL_NOT_EN);
1276  CASE(IS_ONLY_IN_BB_MODE);
1277  CASE(IS_INVALID_COLOR_FORMAT);
1278  CASE(IS_INVALID_WB_BINNING_MODE);
1279  CASE(IS_INVALID_I2C_DEVICE_ADDRESS);
1280  CASE(IS_COULD_NOT_CONVERT);
1281  CASE(IS_TRANSFER_ERROR);
1282  CASE(IS_PARAMETER_SET_NOT_PRESENT);
1283  CASE(IS_INVALID_CAMERA_TYPE);
1284  CASE(IS_INVALID_HOST_IP_HIBYTE);
1285  CASE(IS_CM_NOT_SUPP_IN_CURR_DISPLAYMODE);
1286  CASE(IS_NO_IR_FILTER);
1287  CASE(IS_STARTER_FW_UPLOAD_NEEDED);
1288  CASE(IS_DR_LIBRARY_NOT_FOUND);
1289  CASE(IS_DR_DEVICE_OUT_OF_MEMORY);
1290  CASE(IS_DR_CANNOT_CREATE_SURFACE);
1291  CASE(IS_DR_CANNOT_CREATE_VERTEX_BUFFER);
1292  CASE(IS_DR_CANNOT_CREATE_TEXTURE);
1293  CASE(IS_DR_CANNOT_LOCK_OVERLAY_SURFACE);
1294  CASE(IS_DR_CANNOT_UNLOCK_OVERLAY_SURFACE);
1295  CASE(IS_DR_CANNOT_GET_OVERLAY_DC);
1296  CASE(IS_DR_CANNOT_RELEASE_OVERLAY_DC);
1297  CASE(IS_DR_DEVICE_CAPS_INSUFFICIENT);
1298  CASE(IS_INCOMPATIBLE_SETTING);
1299  CASE(IS_DR_NOT_ALLOWED_WHILE_DC_IS_ACTIVE);
1300  CASE(IS_DEVICE_ALREADY_PAIRED);
1301  CASE(IS_SUBNETMASK_MISMATCH);
1302  CASE(IS_SUBNET_MISMATCH);
1303  CASE(IS_INVALID_IP_CONFIGURATION);
1304  CASE(IS_DEVICE_NOT_COMPATIBLE);
1305  CASE(IS_NETWORK_FRAME_SIZE_INCOMPATIBLE);
1306  CASE(IS_NETWORK_CONFIGURATION_INVALID);
1307  CASE(IS_ERROR_CPU_IDLE_STATES_CONFIGURATION);
1308  default:
1309  return "UNKNOWN ERROR";
1310  }
1311  return "UNKNOWN ERROR";
1312 #undef CASE
1313 }
1314 
1315 
1316 const char* UEyeCamDriver::colormode2str(INT mode) {
1317 #define CASE(s) case s: return #s; break
1318  switch (mode) {
1319  CASE(IS_CM_MONO16);
1320  CASE(IS_CM_MONO12);
1321  CASE(IS_CM_MONO10);
1322  CASE(IS_CM_MONO8);
1323  CASE(IS_CM_SENSOR_RAW16);
1324  CASE(IS_CM_SENSOR_RAW12);
1325  CASE(IS_CM_SENSOR_RAW10);
1326  CASE(IS_CM_SENSOR_RAW8);
1327  CASE(IS_CM_RGB12_UNPACKED);
1328  CASE(IS_CM_RGB10_UNPACKED);
1329  CASE(IS_CM_RGB10_PACKED);
1330  CASE(IS_CM_RGB8_PACKED);
1331  CASE(IS_CM_RGBA12_UNPACKED);
1332  CASE(IS_CM_RGBA8_PACKED);
1333  CASE(IS_CM_RGBY8_PACKED);
1334  CASE(IS_CM_BGR12_UNPACKED);
1335  CASE(IS_CM_BGR10_UNPACKED);
1336  CASE(IS_CM_BGR10_PACKED);
1337  CASE(IS_CM_BGR8_PACKED);
1338  CASE(IS_CM_BGRA12_UNPACKED);
1339  CASE(IS_CM_BGRA8_PACKED);
1340  CASE(IS_CM_BGRY8_PACKED);
1341  CASE(IS_CM_RGB8_PLANAR);
1342  CASE(IS_CM_BGR565_PACKED);
1343  CASE(IS_CM_BGR5_PACKED);
1344  CASE(IS_CM_UYVY_PACKED);
1345  CASE(IS_CM_CBYCRY_PACKED);
1346  CASE(IS_CM_PREFER_PACKED_SOURCE_FORMAT);
1347  CASE(IS_CM_JPEG);
1348  // The following are obsolete formats according to
1349  // https://en.ids-imaging.com/manuals/uEye_SDK/EN/uEye_Manual/index.html
1350  // CASE(IS_SET_CM_RGB32);
1351  // CASE(IS_SET_CM_RGB24);
1352  // CASE(IS_SET_CM_RGB16);
1353  // CASE(IS_SET_CM_RGB15);
1354  // CASE(IS_SET_CM_Y8);
1355  // CASE(IS_SET_CM_BAYER);
1356  // CASE(IS_SET_CM_UYVY);
1357  // CASE(IS_SET_CM_UYVY_MONO);
1358  // CASE(IS_SET_CM_UYVY_BAYER);
1359  // CASE(IS_SET_CM_CBYCRY);
1360  // CASE(IS_SET_CM_RGBY);
1361  // CASE(IS_SET_CM_RGB30);
1362  // CASE(IS_SET_CM_Y12);
1363  // CASE(IS_SET_CM_BAYER12);
1364  // CASE(IS_SET_CM_Y16);
1365  // CASE(IS_SET_CM_BAYER16);
1366  // CASE(IS_CM_BGR10V2_PACKED);
1367  // CASE(IS_CM_RGB10V2_PACKED);
1368  // CASE(IS_CM_BGR555_PACKED);
1369  // CASE(IS_CM_BAYER_RG8);
1370  // CASE(IS_CM_BAYER_RG12);
1371  // CASE(IS_CM_BAYER_RG16);
1372  // CASE(IS_CM_RGB12_PACKED);
1373  // CASE(IS_CM_RGBA12_PACKED);
1374  // CASE(IS_CM_BGR12_PACKED);
1375  // CASE(IS_CM_BGRA12_PACKED);
1376  default:
1377  return "UNKNOWN COLOR MODE";
1378  }
1379  return "UNKNOWN COLOR MODE";
1380 #undef CASE
1381 }
1382 
1383 
1385  switch (mode) {
1386  case IS_CM_SENSOR_RAW8:
1387  case IS_CM_MONO8:
1388  return 8;
1389  case IS_CM_SENSOR_RAW10:
1390  case IS_CM_SENSOR_RAW12:
1391  case IS_CM_SENSOR_RAW16:
1392  case IS_CM_MONO10:
1393  case IS_CM_MONO12:
1394  case IS_CM_MONO16:
1395  case IS_CM_BGR5_PACKED:
1396  case IS_CM_BGR565_PACKED:
1397  case IS_CM_UYVY_PACKED:
1398  case IS_CM_UYVY_MONO_PACKED:
1399  case IS_CM_UYVY_BAYER_PACKED:
1400  case IS_CM_CBYCRY_PACKED:
1401  return 16;
1402  case IS_CM_RGB8_PACKED:
1403  case IS_CM_BGR8_PACKED:
1404  case IS_CM_RGB8_PLANAR:
1405  return 24;
1406  case IS_CM_RGBA8_PACKED:
1407  case IS_CM_BGRA8_PACKED:
1408  case IS_CM_RGBY8_PACKED:
1409  case IS_CM_BGRY8_PACKED:
1410  case IS_CM_RGB10_PACKED:
1411  case IS_CM_BGR10_PACKED:
1412  return 32;
1413  case IS_CM_RGB10_UNPACKED:
1414  case IS_CM_BGR10_UNPACKED:
1415  case IS_CM_RGB12_UNPACKED:
1416  case IS_CM_BGR12_UNPACKED:
1417  return 48;
1418  case IS_CM_RGBA12_UNPACKED:
1419  case IS_CM_BGRA12_UNPACKED:
1420  return 64;
1421 // case IS_CM_JPEG:
1422  default:
1423  return 0;
1424  }
1425 }
1426 
1427 
1429  switch (mode) {
1430  case IS_CM_SENSOR_RAW8:
1431  case IS_CM_SENSOR_RAW10:
1432  case IS_CM_SENSOR_RAW12:
1433  case IS_CM_SENSOR_RAW16:
1434  case IS_CM_MONO8:
1435  case IS_CM_MONO10:
1436  case IS_CM_MONO12:
1437  case IS_CM_MONO16:
1438  case IS_CM_RGB8_PACKED:
1439  case IS_CM_BGR8_PACKED:
1440  case IS_CM_RGB8_PLANAR:
1441  case IS_CM_RGB10_PACKED:
1442  case IS_CM_BGR10_PACKED:
1443  case IS_CM_RGB10_UNPACKED:
1444  case IS_CM_BGR10_UNPACKED:
1445  case IS_CM_RGB12_UNPACKED:
1446  case IS_CM_BGR12_UNPACKED:
1447  return true;
1448 // case IS_CM_BGR5_PACKED:
1449 // case IS_CM_BGR565_PACKED:
1450 // case IS_CM_UYVY_PACKED:
1451 // case IS_CM_UYVY_MONO_PACKED:
1452 // case IS_CM_UYVY_BAYER_PACKED:
1453 // case IS_CM_CBYCRY_PACKED:
1454 // case IS_CM_RGBA8_PACKED:
1455 // case IS_CM_BGRA8_PACKED:
1456 // case IS_CM_RGBY8_PACKED:
1457 // case IS_CM_BGRY8_PACKED:
1458 // case IS_CM_RGBA12_UNPACKED:
1459 // case IS_CM_BGRA12_UNPACKED:
1460 // case IS_CM_JPEG:
1461  default:
1462  return false;
1463  }
1464 }
1465 
1466 
1467 const std::map<std::string, INT> UEyeCamDriver::COLOR_DICTIONARY = {
1468  { "bayer_rggb8", IS_CM_SENSOR_RAW8 },
1469  { "bayer_rggb10", IS_CM_SENSOR_RAW10 },
1470  { "bayer_rggb12", IS_CM_SENSOR_RAW12 },
1471  { "bayer_rggb16", IS_CM_SENSOR_RAW16 },
1472  { "mono8", IS_CM_MONO8 },
1473  { "mono10", IS_CM_MONO10 },
1474  { "mono12", IS_CM_MONO12 },
1475  { "mono16", IS_CM_MONO16 },
1476  { "rgb8", IS_CM_RGB8_PACKED },
1477  { "bgr8", IS_CM_BGR8_PACKED },
1478  { "rgb10", IS_CM_RGB10_PACKED },
1479  { "bgr10", IS_CM_BGR10_PACKED },
1480  { "rgb10u", IS_CM_RGB10_UNPACKED },
1481  { "bgr10u", IS_CM_BGR10_UNPACKED },
1482  { "rgb12u", IS_CM_RGB12_UNPACKED },
1483  { "bgr12u", IS_CM_BGR12_UNPACKED }
1484 };
1485 
1486 
1487 INT UEyeCamDriver::name2colormode(const std::string& name) {
1488  const std::map<std::string, INT>::const_iterator iter = COLOR_DICTIONARY.find(name);
1489  if (iter!=COLOR_DICTIONARY.end()) {
1490  return iter->second;
1491  }
1492  else {
1493  return 0;
1494  }
1495 }
1496 
1497 
1498 const std::string UEyeCamDriver::colormode2name(INT mode) {
1499  for (const std::pair<std::string, INT>& value: COLOR_DICTIONARY) {
1500  if (value.second == mode) {
1501  return value.first;
1502  }
1503  }
1504  return std::string();
1505 }
1506 
1507 
1508 const std::function<void*(void*, void*, size_t)> UEyeCamDriver::getUnpackCopyFunc(INT color_mode) {
1509  switch (color_mode) {
1510  case IS_CM_RGB10_PACKED:
1511  case IS_CM_BGR10_PACKED:
1512  return unpackRGB10;
1513  case IS_CM_SENSOR_RAW10:
1514  case IS_CM_MONO10:
1515  case IS_CM_RGB10_UNPACKED:
1516  case IS_CM_BGR10_UNPACKED:
1517  return unpack10u;
1518  case IS_CM_SENSOR_RAW12:
1519  case IS_CM_MONO12:
1520  case IS_CM_RGB12_UNPACKED:
1521  case IS_CM_BGR12_UNPACKED:
1522  return unpack12u;
1523  default:
1524  return memcpy;
1525  }
1526 }
1527 
1528 
1529 void* UEyeCamDriver::unpackRGB10(void* dst, void* src, size_t num) {
1530  // UEye Driver 4.80.2 Linux 64 bit:
1531  // pixel format seems to be
1532  // 00BBBBBB BBBBGGGG GGGGGGRR RRRRRRRR
1533  // instead of documented
1534  // RRRRRRRR RRGGGGGG GGGGBBBB BBBBBB00
1535 
1536  uint32_t pixel;
1537  uint32_t* from = static_cast<uint32_t*>(src);
1538  uint16_t* to = static_cast<uint16_t*>(dst);
1539  // unpack a whole pixels per iteration
1540  for (size_t i=0; i<num/4; ++i) {
1541  pixel = (*from);
1542  to[0] = static_cast<unsigned short>(pixel);
1543  to[0] <<= 6;
1544  pixel >>= 4;
1545  to[1] = static_cast<unsigned short>(pixel);
1546  to[1] &= 0b1111111111000000;
1547  pixel >>= 10;
1548  to[2] = static_cast<unsigned short>(pixel);
1549  to[2] &= 0b1111111111000000;
1550  to+=3;
1551  ++from;
1552  }
1553  return dst;
1554 }
1555 
1556 
1557 void* UEyeCamDriver::unpack10u(void* dst, void* src, size_t num) {
1558  // UEye Driver 4.80.2 Linux 64 bit:
1559  // pixel format seems to be
1560  // 000000CC CCCCCCCC
1561  // instead of documented
1562  // CCCCCCCC CC000000
1563  uint16_t* from = static_cast<uint16_t*>(src);
1564  uint16_t* to = static_cast<uint16_t*>(dst);
1565  // unpack one color per iteration
1566  for (size_t i=0; i<num/2; ++i) {
1567  to[i] = from[i];
1568  to[i] <<= 6;
1569  }
1570  return dst;
1571 }
1572 
1573 
1574 void* UEyeCamDriver::unpack12u(void* dst, void* src, size_t num) {
1575  // UEye Driver 4.80.2 Linux 64 bit:
1576  // pixel format seems to be
1577  // 0000CCCC CCCCCCCC
1578  // instead of documented
1579  // CCCCCCCC CCCC0000
1580  uint16_t* from = static_cast<uint16_t*>(src);
1581  uint16_t* to = static_cast<uint16_t*>(dst);
1582  // unpack one color per iteration
1583  for (size_t i=0; i<num/2; ++i) {
1584  to[i] = from[i];
1585  to[i] <<= 4;
1586  }
1587  return dst;
1588 }
1589 
1590 
1591 bool UEyeCamDriver::getTimestamp(UEYETIME *timestamp) {
1592  UEYEIMAGEINFO ImageInfo;
1593  if(is_GetImageInfo (cam_handle_, cam_buffer_id_, &ImageInfo, sizeof (ImageInfo)) == IS_SUCCESS) {
1594  *timestamp = ImageInfo.TimestampSystem;
1595  return true;
1596  }
1597  return false;
1598 }
1599 
1600 
1601 bool UEyeCamDriver::getClockTick(uint64_t *tick) {
1602  UEYEIMAGEINFO ImageInfo;
1603  if(is_GetImageInfo (cam_handle_, cam_buffer_id_, &ImageInfo, sizeof (ImageInfo)) == IS_SUCCESS) {
1604  *tick = ImageInfo.u64TimestampDevice;
1605  return true;
1606  }
1607  return false;
1608 }
1609 
1610 } // namespace ueye_cam
virtual INT connectCam(int new_cam_ID=-1)
static void * unpackRGB10(void *dst, void *src, size_t num)
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)
INT setMirrorLeftRight(bool flip_vertical)
#define IS_BINNING_8X
#define CASE(s)
#define IS_BINNING_16X
INT setFlashParams(INT &delay_us, UINT &duration_us)
XmlRpcServer s
bool getTimestamp(UEYETIME *timestamp)
#define WARN_STREAM(...)
#define CAP(val, min, max)
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(...)
static bool isSupportedColorMode(INT mode)
#define IS_SUBSAMPLING_2X
#define IS_BINNING_2X
#define DEBUG_STREAM(...)
INT setSensorScaling(double &rate, bool reallocate_buffer=true)
#define ERROR_STREAM(...)
INT setPixelClockRate(INT &clock_rate_mhz)
#define IS_SUBSAMPLING_4X
static INT name2colormode(const std::string &name)
static const char * err2str(INT error)
unsigned int cam_subsampling_rate_
INT setSubsampling(int &rate, bool reallocate_buffer=true)
INT setResolution(INT &image_width, INT &image_height, INT &image_left, INT &image_top, bool reallocate_buffer=true)
static const char * colormode2str(INT mode)
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
INT setBinning(int &rate, bool reallocate_buffer=true)
INT setFrameRate(bool &auto_frame_rate, double &frame_rate_hz)
static INT colormode2bpp(INT mode)
static void * unpack10u(void *dst, void *src, size_t num)
#define IS_BINNING_4X
static void * unpack12u(void *dst, void *src, size_t num)
static const std::map< std::string, INT > COLOR_DICTIONARY
bool getClockTick(uint64_t *tick)
#define IS_SUBSAMPLING_8X
INT setSoftwareGamma(INT &software_gamma)
INT loadCamConfig(std::string filename, bool ignore_load_failure=true)
#define IS_SUBSAMPLING_16X
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