ueye_cam_driver.hpp
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 
48 #ifndef UEYE_CAM_DRIVER_HPP_
49 #define UEYE_CAM_DRIVER_HPP_
50 
51 
52 #include <ueye.h>
53 #include <string>
54 #include <thread>
55 #include <functional>
56 #include "logging_macros.hpp"
57 
58 
59 namespace ueye_cam {
60 
61 
62 #define CAP(val, min, max) \
63  if (val < min) { \
64  val = min; \
65  } else if (val > max) { \
66  val = max; \
67  }
68 
69 #define IS_SUBSAMPLING_2X (IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL)
70 #define IS_SUBSAMPLING_4X (IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL)
71 #define IS_SUBSAMPLING_8X (IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL)
72 #define IS_SUBSAMPLING_16X (IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL)
73 
74 #define IS_BINNING_2X (IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL)
75 #define IS_BINNING_4X (IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL)
76 #define IS_BINNING_8X (IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL)
77 #define IS_BINNING_16X (IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL)
78 
79 
84 public:
85  constexpr static int ANY_CAMERA = 0;
86 
87 
91  UEyeCamDriver(int cam_ID = ANY_CAMERA, std::string cam_name = "camera");
92 
96  virtual ~UEyeCamDriver();
97 
105  virtual INT connectCam(int new_cam_ID = -1);
106 
112  virtual INT disconnectCam();
113 
122  INT loadCamConfig(std::string filename, bool ignore_load_failure = true);
123 
137  INT setColorMode(std::string& mode, bool reallocate_buffer = true);
138 
157  INT setResolution(INT& image_width, INT& image_height, INT& image_left,
158  INT& image_top, bool reallocate_buffer = true);
159 
170  INT setSubsampling(int& rate, bool reallocate_buffer = true);
171 
182  INT setBinning(int& rate, bool reallocate_buffer = true);
183 
194  INT setSensorScaling(double& rate, bool reallocate_buffer = true);
195 
213  INT setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
214  INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost);
215 
225  INT setSoftwareGamma(INT& software_gamma);
226 
239  INT setExposure(bool& auto_exposure, double& auto_exposure_reference, double& exposure_ms);
240 
252  INT setWhiteBalance(bool& auto_white_balance, INT& red_offset, INT& blue_offset);
253 
268  INT setFrameRate(bool& auto_frame_rate, double& frame_rate_hz);
269 
278  INT setPixelClockRate(INT& clock_rate_mhz);
279 
289  INT setFlashParams(INT& delay_us, UINT& duration_us);
290 
300  INT setGpioMode(const INT& gpio, INT& mode, double& pwm_freq, double& pwm_duty_cycle);
301 
321  INT setFreeRunMode();
322 
337  INT setExtTriggerMode();
338 
345  INT setStandbyMode();
346 
353  INT setMirrorUpsideDown(bool flip_horizontal);
354 
361  INT setMirrorLeftRight(bool flip_vertical);
362 
376  const char* processNextFrame(UINT timeout_ms);
377 
378  inline bool isConnected() { return (cam_handle_ != HIDS(0)); }
379 
380  inline bool freeRunModeActive() {
381  return ((cam_handle_ != HIDS(0)) &&
382  (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_OFF) &&
383  (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
384  }
385 
386  inline bool extTriggerModeActive() {
387  return ((cam_handle_ != HIDS(0)) &&
388  (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_HI_LO) &&
389  (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
390  }
391 
392  inline bool isCapturing() {
393  return ((cam_handle_ != HIDS(0)) &&
394  (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
395  }
396 
400  const static char* err2str(INT error);
401 
405  const static char* colormode2str(INT mode);
406 
410  const static std::string colormode2img_enc(INT mode);
411 
415  static INT colormode2bpp(INT mode);
416 
420  static bool isSupportedColorMode(INT mode);
421 
425  static INT name2colormode(const std::string& name);
426  const static std::string colormode2name(INT mode);
427 
432  const static std::function<void*(void*, void*, size_t)> getUnpackCopyFunc(INT color_mode);
433  static void* unpackRGB10(void* dst, void* src, size_t num);
434  static void* unpack10u(void* dst, void* src, size_t num);
435  static void* unpack12u(void* dst, void* src, size_t num);
436 
440  bool getTimestamp(UEYETIME *timestamp);
441 
445  bool getClockTick(uint64_t *tick);
446 
447 
448 protected:
467  virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
468 
469 
470  virtual void handleTimeout() {}
471 
472 
479  INT reallocateCamBuffer();
480 
481  const static std::map<std::string, INT> COLOR_DICTIONARY;
482 
484  SENSORINFO cam_sensor_info_;
485  char* cam_buffer_;
488  unsigned int cam_buffer_size_;
489  std::string cam_name_;
490  int cam_id_;
491  IS_RECT cam_aoi_;
492  unsigned int cam_subsampling_rate_;
493  unsigned int cam_binning_rate_;
497 };
498 
499 
500 } // namespace ueye_cam
501 
502 
503 #endif /* UEYE_CAM_DRIVER_HPP_ */
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)
static constexpr int ANY_CAMERA
INT setFlashParams(INT &delay_us, UINT &duration_us)
bool getTimestamp(UEYETIME *timestamp)
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)
static bool isSupportedColorMode(INT mode)
INT setSensorScaling(double &rate, bool reallocate_buffer=true)
INT setPixelClockRate(INT &clock_rate_mhz)
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")
static const std::string colormode2img_enc(INT mode)
INT setBinning(int &rate, bool reallocate_buffer=true)
INT setFrameRate(bool &auto_frame_rate, double &frame_rate_hz)
UEyeCamDriver(int cam_ID=ANY_CAMERA, std::string cam_name="camera")
static INT colormode2bpp(INT mode)
static void * unpack10u(void *dst, void *src, size_t num)
static void * unpack12u(void *dst, void *src, size_t num)
static const std::map< std::string, INT > COLOR_DICTIONARY
bool getClockTick(uint64_t *tick)
INT setSoftwareGamma(INT &software_gamma)
INT loadCamConfig(std::string filename, bool ignore_load_failure=true)
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