Camera.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012-2016, Kevin Hallenbeck
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Kevin Hallenbeck nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ueye/Camera.h>
36 
37 // Check expected uEye SDK version in ueye.h for supported architectures
38 #if defined(__i386) || defined(__i386__) || defined(_M_IX86)
39  #define EXPECTED_VERSION_MAJOR 4
40  #define EXPECTED_VERSION_MINOR 60
41  #define EXPECTED_VERSION_BUILD 5
42  #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
43  #warning Expected ueye driver version 4.60.x. Different version found in ueye.h.
44  #endif
45 #elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64)
46  #define EXPECTED_VERSION_MAJOR 4
47  #define EXPECTED_VERSION_MINOR 60
48  #define EXPECTED_VERSION_BUILD 5
49  #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
50  #warning Expected ueye driver version 4.60.x. Different version found in ueye.h.
51  #endif
52 #elif defined(__arm__) || defined(__TARGET_ARCH_ARM)
53  #define EXPECTED_VERSION_MAJOR 4
54  #define EXPECTED_VERSION_MINOR 60
55  #define EXPECTED_VERSION_BUILD 0
56  #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
57  #warning Expected ueye driver version 4.60.x. Different version found in ueye.h.
58  #endif
59 #elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64)
60  #define EXPECTED_VERSION_MAJOR 0
61  #define EXPECTED_VERSION_MINOR 0
62  #define EXPECTED_VERSION_BUILD 0
63  #warning Architecture ia64 not explicitly supported.
64 #elif defined(__ppc__) || defined(__ppc) || defined(__powerpc__) || defined(_ARCH_COM) || defined(_ARCH_PWR) || defined(_ARCH_PPC) || defined(_M_MPPC) || defined(_M_PPC)
65  #define EXPECTED_VERSION_MAJOR 0
66  #define EXPECTED_VERSION_MINOR 0
67  #define EXPECTED_VERSION_BUILD 0
68  #warning Architecture ppc not explicitly supported.
69 #else
70  #define EXPECTED_VERSION_MAJOR 0
71  #define EXPECTED_VERSION_MINOR 0
72  #define EXPECTED_VERSION_BUILD 0
73  #warning Architecture not explicitly supported. Supported: amd64, i386, arm.
74 #endif
75 
76 
77 namespace ueye
78 {
79 
81 {
82  streaming_ = false;
83  stop_capture_ = false;
85  auto_exposure_ = false;
86  exposure_time_ = 99.0;
87  hardware_gamma_ = true;
88  gain_boost_ = false;
89  zoom_ = 1;
90  pixel_clock_ = 20;
91  auto_gain_ = false;
92  hardware_gain_ = 100;
93  frame_rate_ = 5.0;
94  flash_global_params_ = false;
95  serial_number_ = 0;
96  cam_ = 0;
97  memset(&cam_info_, 0x00, sizeof(cam_info_));
98  stream_callback_ = NULL;
99 }
100 
102 {
104 }
105 
106 #define STR_HELPER(x) #x
107 #define STR(x) STR_HELPER(x)
108 bool Camera::checkVersion(int &major, int &minor, int &build, const char *&expected)
109 {
111  build = is_GetDLLVersion();
112  major = (build >> 24) & 0x000000FF;
113  minor = (build >> 16) & 0x000000FF;
114  build &= 0x0000FFFF;
115  if ((major == EXPECTED_VERSION_MAJOR) && (minor == EXPECTED_VERSION_MINOR) && (build == EXPECTED_VERSION_BUILD)) {
116  return true;
117  }
118  return false;
119 }
120 #undef STR_HELPER
121 #undef STR
122 
124 {
125  int num = 0;
126  checkError(is_GetNumberOfCameras(&num));
127  return num;
128 }
129 
130 unsigned int Camera::getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id)
131 {
132  int num = getNumberOfCameras();
133  if (num > 0) {
134  UEYE_CAMERA_LIST *list = (UEYE_CAMERA_LIST *)malloc(sizeof(DWORD) + num * sizeof(UEYE_CAMERA_INFO));
135  list->dwCount = num;
136  if (is_GetCameraList(list) == IS_SUCCESS) {
137  num = list->dwCount;
138  serial.resize(num);
139  dev_id.resize(num);
140  for (int i = 0; i < num; i++) {
141  serial[i] = atoll(list->uci[i].SerNo);
142  dev_id[i] = list->uci[i].dwDeviceID;
143  }
144  } else {
145  num = 0;
146  }
147  free(list);
148  return num;
149  }
150  return 0;
151 }
152 
153 bool Camera::openCameraCamId(unsigned int id)
154 {
155  if (getNumberOfCameras() < 1) {
156  return false;
157  }
158 
159  cam_ = id;
160  checkError(is_InitCamera(&cam_, 0));
161 
162  checkError(is_GetSensorInfo(cam_, &cam_info_));
163  CAMINFO info;
164  checkError(is_GetCameraInfo(cam_, &info));
165  serial_number_ = atoll(info.SerNo);
166 
169  if (!auto_exposure_) {
171  }
175  if (!auto_gain_) {
177  }
178  setZoom(&zoom_);
181  return true;
182 }
183 bool Camera::openCameraDevId(unsigned int id)
184 {
185  return openCameraCamId(id | IS_USE_DEVICE_ID);
186 }
187 bool Camera::openCameraSerNo(unsigned int serial_number)
188 {
189  std::vector<unsigned int> serial;
190  std::vector<unsigned int> dev_id;
191  unsigned int num = getSerialNumberList(serial, dev_id);
192  for (unsigned int i = 0; i < num; i++) {
193  if (serial[i] == serial_number) {
194  return openCameraDevId(dev_id[i]);
195  }
196  }
197  return false;
198 }
199 
201 {
202  switch (mode) {
203  case MONO8:
204  return "mono8";
205  case MONO16:
206  return "mono16";
207  case BGR5:
208  return "bgr5";
209  case BGR565:
210  return "bgr565";
211  case YUV:
212  return "yuv422";
213  case YCbCr:
214  return "ycbcr422";
215  case BGR8:
216  return "bgr8";
217  case RGB8:
218  return "rgb8";
219  case BGRA8:
220  case BGRY8:
221  return "bgra8";
222  case RGBA8:
223  case RGBY8:
224  return "rgba8";
225  }
226  return "";
227 }
228 
230 {
231  double time_ms;
232  checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_GET_EXPOSURE, &time_ms, sizeof(double)));
233  return time_ms;
234 }
236 {
237  hardware_gain_ = is_SetHWGainFactor(cam_, IS_GET_MASTER_GAIN_FACTOR, 0);
238  return hardware_gain_;
239 }
241 {
242  return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_EXTERNALTRIGGER);
243 }
245 {
246  return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_SUPPORTED_TRIGGER_MODE);
247 }
248 
250 {
251  bool restart = streaming_ && (stream_callback_ != NULL);
253  if (is_SetColorMode(cam_, mode) != IS_SUCCESS) {
254  mode = MONO8;
255  is_SetColorMode(cam_, mode);
256  }
257  color_mode_ = mode;
258  if (restart) {
260  }
261 }
262 void Camera::setAutoExposure(bool *enable)
263 {
264  double param1 = *enable ? 1.0 : 0.0;
265  double param2 = 0;
266  if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2)) {
267  param1 = 0;
268  is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2);
269  *enable = false;
270  }
271  auto_exposure_ = *enable;
272 }
273 void Camera::setExposure(double *time_ms)
274 {
275  bool b = false;
276  setAutoExposure(&b);
277  checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_SET_EXPOSURE, time_ms, sizeof(double)));
279  exposure_time_ = *time_ms;
280 }
281 void Camera::setHardwareGamma(bool *enable)
282 {
283  if (*enable) {
284  if (IS_SUCCESS != is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_ON)) {
285  is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
286  *enable = false;
287  }
288  } else {
289  is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
290  }
291  hardware_gamma_ = *enable;
292 }
293 void Camera::setZoom(int *zoom)
294 {
295  if (zoom_ != *zoom) {
296  // Reset zoom
297  is_SetSubSampling(cam_, 0);
298  is_SetBinning(cam_, 0);
299 
300  // Try Subsampling then Binning
301  if (IS_SUCCESS != is_SetSubSampling(cam_, getSubsampleParam(zoom))) {
302  is_SetSubSampling(cam_, 0);
303  if (IS_SUCCESS != is_SetBinning(cam_, getBinningParam(zoom))) {
304  is_SetBinning(cam_, 0);
305  *zoom = 1;
306  }
307  }
308 
309  // Zoom affects the frame-rate and needs a restart to change the buffer sizes
310  is_HotPixel(cam_, IS_HOTPIXEL_ENABLE_CAMERA_CORRECTION, NULL, 0);
313  }
314  zoom_ = *zoom;
315 }
316 void Camera::setPixelClock(int *MHz)
317 {
318  int pixelClockList[150]; // No camera has more than 150 different pixel clocks (uEye manual)
319  int numberOfSupportedPixelClocks = 0;
320  checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_GET_NUMBER, &numberOfSupportedPixelClocks, sizeof(numberOfSupportedPixelClocks)));
321  if(numberOfSupportedPixelClocks > 0) {
322  memset(pixelClockList, 0x00, sizeof(pixelClockList));
323  checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_GET_LIST, pixelClockList, numberOfSupportedPixelClocks * sizeof(int)));
324  }
325  int minPixelClock = pixelClockList[0];
326  int maxPixelClock = pixelClockList[numberOfSupportedPixelClocks-1];
327 
328  // As list is sorted smallest to largest...
329  for(int i = 0; i < numberOfSupportedPixelClocks; i++) {
330  if(*MHz <= pixelClockList[i]) {
331  *MHz = pixelClockList[i]; // ...get the closest-larger-or-equal from the list
332  break;
333  }
334  }
335 
336  if (*MHz < minPixelClock) {
337  *MHz = minPixelClock; // Clip to min
338  }
339  if (*MHz > maxPixelClock) {
340  *MHz = maxPixelClock; // Clip to max
341  }
342 
343  checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_SET, MHz, sizeof(int)));
345 
346  pixel_clock_ = *MHz;
347 }
348 void Camera::setFrameRate(double *rate)
349 {
350  checkError(is_SetFrameRate(cam_, *rate, rate));
352  frame_rate_ = *rate;
353 }
354 void Camera::setGainBoost(bool *enable)
355 {
356  if (is_SetGainBoost(cam_, IS_GET_SUPPORTED_GAINBOOST) == IS_SET_GAINBOOST_ON) {
357  if (*enable)
358  is_SetGainBoost(cam_, IS_SET_GAINBOOST_ON);
359  else
360  is_SetGainBoost(cam_, IS_SET_GAINBOOST_OFF);
361  gain_boost_ = is_SetGainBoost(cam_, IS_GET_GAINBOOST) == IS_SET_GAINBOOST_ON;
362  } else {
363  gain_boost_ = false;
364  }
365  *enable = gain_boost_;
366 }
367 void Camera::setAutoGain(bool *enable)
368 {
369  double param1 = *enable ? 1.0 : 0.0;
370  double param2 = 0;
371  if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2)) {
372  param1 = 0;
373  is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2);
374  *enable = false;
375  }
376  auto_gain_ = *enable;
377 }
378 void Camera::setHardwareGain(int *gain)
379 {
380  bool b = false;
381  setAutoGain(&b);
382  if (*gain < 0)
383  *gain = 0;
384  if (*gain > 400)
385  *gain = 400;
386  hardware_gain_ = is_SetHWGainFactor(cam_, IS_SET_MASTER_GAIN_FACTOR, *gain);
387  *gain = hardware_gain_;
388 }
390 {
391  if ((mode == 0) || (mode & getSupportedTriggers())) {
392  if (is_SetExternalTrigger(cam_, mode) == IS_SUCCESS) {
393  return true;
394  }
395  }
396  return false;
397 }
399 {
400  UINT m = mode;
401  switch (mode) {
406  flash_global_params_ = true;
407  break;
408 
409  case FLASH_CONSTANT_HIGH:
410  case FLASH_CONSTANT_LOW:
411  flash_global_params_ = false;
412  break;
413 
414  case FLASH_OFF:
415  default:
416  flash_global_params_ = false;
417  m = FLASH_OFF;
418  break;
419  }
420  checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&m, sizeof(m)));
422 }
423 void Camera::setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec)
424 {
425  int num_mode = int(mode);
426 
427  checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&num_mode, sizeof(num_mode)));
428 
429  if (mode != FLASH_OFF) {
430  IO_FLASH_PARAMS params;
431  memset(&params, 0, sizeof(params));
432 
433  params.s32Delay = delay_usec;
434  params.u32Duration = duration_usec;
435 
436  checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_PARAMS, &params, sizeof(params)));
437  }
438 
439  flash_global_params_ = false;
440 }
442 {
443  // If flash delay = 0 and flash duration = 0, the flash signal is
444  // automatically synchronized to the exposure time.
445  setFlash(mode, 0, 0);
446 }
448 {
449  if (flash_global_params_) {
450  IO_FLASH_PARAMS params;
451  checkError(is_IO(cam_, IS_IO_CMD_FLASH_GET_GLOBAL_PARAMS, (void*)&params, sizeof(params)));
452  checkError(is_IO(cam_, IS_IO_CMD_FLASH_APPLY_GLOBAL_PARAMS, NULL, 0));
453  }
454 }
455 void Camera::setTriggerDelay(int delay_usec)
456 {
457  checkError(is_SetTriggerDelay(cam_, delay_usec));
458 }
459 
461 {
462  if (streaming_)
463  return is_ForceTrigger(cam_) == IS_SUCCESS;
464  return false;
465 }
466 
468 {
469  int param;
470  switch (*scale) {
471  case 2:
472  param = IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL;
473  break;
474  case 3:
475  param = IS_SUBSAMPLING_3X_VERTICAL | IS_SUBSAMPLING_3X_HORIZONTAL;
476  break;
477  case 4:
478  param = IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL;
479  break;
480  case 5:
481  param = IS_SUBSAMPLING_5X_VERTICAL | IS_SUBSAMPLING_5X_HORIZONTAL;
482  break;
483  case 6:
484  param = IS_SUBSAMPLING_6X_VERTICAL | IS_SUBSAMPLING_6X_HORIZONTAL;
485  break;
486  case 7:
487  case 8:
488  *scale = 8;
489  param = IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL;
490  break;
491  case 9:
492  case 10:
493  case 11:
494  case 12:
495  case 13:
496  case 14:
497  case 15:
498  case 16:
499  *scale = 16;
500  param = IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL;
501  break;
502  default:
503  *scale = 1;
504  param = IS_SUBSAMPLING_DISABLE;
505  break;
506  }
507  return param;
508 }
509 int Camera::getBinningParam(int *scale)
510 {
511  int param;
512  switch (*scale) {
513  case 2:
514  param = IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL;
515  break;
516  case 3:
517  param = IS_BINNING_3X_VERTICAL | IS_BINNING_3X_HORIZONTAL;
518  break;
519  case 4:
520  param = IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL;
521  break;
522  case 5:
523  param = IS_BINNING_5X_VERTICAL | IS_BINNING_5X_HORIZONTAL;
524  break;
525  case 6:
526  param = IS_BINNING_6X_VERTICAL | IS_BINNING_6X_HORIZONTAL;
527  break;
528  case 7:
529  case 8:
530  *scale = 8;
531  param = IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL;
532  break;
533  case 9:
534  case 10:
535  case 11:
536  case 12:
537  case 13:
538  case 14:
539  case 15:
540  case 16:
541  *scale = 16;
542  param = IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL;
543  break;
544  default:
545  *scale = 1;
546  param = IS_BINNING_DISABLE;
547  break;
548  }
549  return param;
550 }
551 
553 {
554  if (cam_ > 0) {
555  // Release camera and all associated memory
556  checkError(IS_SUCCESS != is_ExitCamera(cam_));
558  }
559 }
560 
562 {
563  closeCamera();
564 }
565 
567 {
568  int bits = 32;
569  switch (color_mode_) {
570  case MONO8:
571  bits = 8;
572  break;
573  case MONO16:
574  case BGR5:
575  case BGR565:
576  case YUV:
577  case YCbCr:
578  bits = 16;
579  break;
580  case BGR8:
581  case RGB8:
582  bits = 24;
583  break;
584  case BGRA8:
585  case BGRY8:
586  case RGBA8:
587  case RGBY8:
588  bits = 32;
589  break;
590  }
591 
592  int width = getWidth();
593  int height = getHeight();
594  if (size < 2) {
595  size = 2;
596  }
597  img_mem_.resize(size);
598  img_mem_id_.resize(size);
599  for (int i = 0; i < size; i++) {
600  if (IS_SUCCESS != is_AllocImageMem(cam_, width, height, bits, &img_mem_[i], &img_mem_id_[i])) {
601  throw uEyeException(-1, "Failed to initialize memory.");
602  }
603  //add memory to memory pool
604  if (IS_SUCCESS != is_SetImageMem(cam_, img_mem_[i], img_mem_id_[i])) {
605  throw uEyeException(-1, "Failed to initialize memory.");
606  }
607  }
608 }
610 {
611  for (int i = 0; i < img_mem_.size(); i++) {
612  checkError(is_FreeImageMem(cam_, img_mem_[i], img_mem_id_[i]));
613  }
614  img_mem_.clear();
615  img_mem_id_.clear();
616 }
617 
619 {
620  streaming_ = true;
621  stop_capture_ = false;
622 
623  initMemoryPool(4);
624 
625  // Setup video event
626  checkError(is_EnableEvent(cam_, IS_SET_EVENT_FRAME));
627 
628  // There is a weird condition with the uEye SDK 4.30 where
629  // this never returns when using IS_WAIT.
630  // We are using IS_DONT_WAIT and retry every 0.1s for 2s instead
631  bool capture = false;
632  for (int i = 0; i < 20; ++i) {
633  if (is_CaptureVideo(cam_, IS_DONT_WAIT) == IS_SUCCESS) {
634  capture = true;
635  break;
636  }
637  usleep(100000); // 100ms
638  }
639  if (!capture) {
640  throw uEyeException(-1, "Capture could not be started.");
641  }
642 
643  size_t depth = 0;
644  switch (color_mode_) {
645  case MONO8:
646  depth = 1;
647  break;
648  case MONO16:
649  case BGR5:
650  case BGR565:
651  depth = 1;
652  break;
653  case YUV:
654  case YCbCr:
655  depth = 2;
656  break;
657  case BGR8:
658  case RGB8:
659  depth = 3;
660  break;
661  case BGRA8:
662  case BGRY8:
663  case RGBA8:
664  case RGBY8:
665  depth = 4;
666  break;
667  default:
668  throw uEyeException(-1, "Unsupported color mode when initializing image header.");
669  return;
670  }
671  size_t size = (size_t)getWidth() * (size_t)getHeight() * depth;
672 
673  char *img_mem;
674  while (!stop_capture_) {
675  // Wait for image. Timeout after 2*FramePeriod = (2000ms/FrameRate)
676  if (is_WaitEvent(cam_, IS_SET_EVENT_FRAME, (int)(2000 / frame_rate_)) == IS_SUCCESS) {
677  if (is_GetImageMem(cam_, (void**)&img_mem) == IS_SUCCESS) {
678  callback(img_mem, size);
679  }
680  }
681  }
682 
683  // Stop video event
684  checkError(is_DisableEvent(cam_, IS_SET_EVENT_FRAME));
685  checkError(is_StopLiveVideo(cam_, IS_WAIT));
686 
688  streaming_ = false;
689 }
690 
692 {
693  stream_callback_ = callback;
694  thread_ = boost::thread(&Camera::captureThread, this, callback);
695 }
697 {
698  stop_capture_ = true;
699  if (thread_.joinable()) {
700  forceTrigger();
701  thread_.join();
702  }
703 }
705 {
706  if (streaming_) {
707  if (stream_callback_ != NULL) {
710  }
711  }
712 }
713 
714 } //namespace ueye
double frame_rate_
Definition: Camera.h:187
unsigned int getHardwareGain()
Definition: Camera.cpp:235
void flashUpdateGlobalParams()
Definition: Camera.cpp:447
boost::function< void(const char *, size_t)> CamCaptureCB
Definition: Camera.h:145
bool forceTrigger()
Definition: Camera.cpp:460
bool param(const std::string &param_name, T &param_val, const T &default_val)
void setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec)
Definition: Camera.cpp:423
void setHardwareGain(int *gain)
Definition: Camera.cpp:378
Definition: Camera.h:44
TriggerMode getTriggerMode()
Definition: Camera.cpp:240
std::vector< char * > img_mem_
Definition: Camera.h:171
#define EXPECTED_VERSION_BUILD
Definition: Camera.cpp:72
void captureThread(CamCaptureCB callback)
Definition: Camera.cpp:618
static const char * colorModeToString(uEyeColor mode)
Definition: Camera.cpp:200
volatile bool stop_capture_
Definition: Camera.h:194
int zoom_
Definition: Camera.h:183
int getBinningParam(int *scale)
Definition: Camera.cpp:509
bool flash_global_params_
Definition: Camera.h:188
bool auto_exposure_
Definition: Camera.h:179
void setAutoGain(bool *enable)
Definition: Camera.cpp:367
bool setTriggerMode(TriggerMode mode)
Definition: Camera.cpp:389
volatile bool streaming_
Definition: Camera.h:193
unsigned int getSerialNumberList(std::vector< unsigned int > &serial, std::vector< unsigned int > &dev_id)
Definition: Camera.cpp:130
void setZoom(int *zoom)
Definition: Camera.cpp:293
void setTriggerDelay(int delay_usec)
Definition: Camera.cpp:455
void stopVideoCapture()
Definition: Camera.cpp:696
void setHardwareGamma(bool *enable)
Definition: Camera.cpp:281
SENSORINFO cam_info_
Definition: Camera.h:190
int getWidth() const
Definition: Camera.h:112
#define EXPECTED_VERSION_MAJOR
Definition: Camera.cpp:70
#define STR(x)
Definition: Camera.cpp:107
void setAutoExposure(bool *enable)
Definition: Camera.cpp:262
void initMemoryPool(int size)
Definition: Camera.cpp:566
void closeCamera()
Definition: Camera.cpp:552
void initPrivateVariables()
Definition: Camera.cpp:80
bool openCameraDevId(unsigned int id)
Definition: Camera.cpp:183
TriggerMode
Definition: Camera.h:71
int hardware_gain_
Definition: Camera.h:186
std::vector< int > img_mem_id_
Definition: Camera.h:172
void setGainBoost(bool *enable)
Definition: Camera.cpp:354
int getNumberOfCameras() const
Definition: Camera.cpp:123
bool gain_boost_
Definition: Camera.h:182
uEyeColor
Definition: Camera.h:56
void startVideoCapture(CamCaptureCB)
Definition: Camera.cpp:691
void setPixelClock(int *MHz)
Definition: Camera.cpp:316
#define EXPECTED_VERSION_MINOR
Definition: Camera.cpp:71
void setFlashWithGlobalParams(FlashMode mode)
Definition: Camera.cpp:398
boost::thread thread_
Definition: Camera.h:196
HIDS cam_
Definition: Camera.h:189
double exposure_time_
Definition: Camera.h:180
uEyeColor color_mode_
Definition: Camera.h:178
void setColorMode(uEyeColor mode)
Definition: Camera.cpp:249
FlashMode
Definition: Camera.h:80
bool auto_gain_
Definition: Camera.h:185
TriggerMode getSupportedTriggers()
Definition: Camera.cpp:244
void setFrameRate(double *rate)
Definition: Camera.cpp:348
int getSubsampleParam(int *scale)
Definition: Camera.cpp:467
double getExposure()
Definition: Camera.cpp:229
bool openCameraSerNo(unsigned int serial_number)
Definition: Camera.cpp:187
void setExposure(double *time_ms)
Definition: Camera.cpp:273
static bool checkVersion(int &major, int &minor, int &build, const char *&expected)
Definition: Camera.cpp:108
void checkError(INT err) const
Definition: Camera.h:152
void restartVideoCapture()
Definition: Camera.cpp:704
int getHeight() const
Definition: Camera.h:113
bool openCameraCamId(unsigned int id)
Definition: Camera.cpp:153
int pixel_clock_
Definition: Camera.h:184
unsigned int serial_number_
Definition: Camera.h:191
void destroyMemoryPool()
Definition: Camera.cpp:609
bool hardware_gamma_
Definition: Camera.h:181
CamCaptureCB stream_callback_
Definition: Camera.h:195


ueye
Author(s): Kevin Hallenbeck
autogenerated on Sun Oct 6 2019 03:35:25