Camera.h
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 #ifndef UEYE_CAMERA_H_
36 #define UEYE_CAMERA_H_
37 
38 #include <ueye.h>
39 #include <stdexcept>
40 #include <string>
41 #include <boost/function.hpp>
42 #include <boost/thread.hpp>
43 
44 namespace ueye
45 {
46 
47 struct uEyeException : public std::runtime_error
48 {
50  uEyeException(int code, const char* msg) :
51  std::runtime_error(msg), error_code(code)
52  {
53  }
54 };
55 
57 {
58  MONO8 = IS_CM_MONO8,
59  MONO16 = IS_CM_MONO16,
60  YUV = IS_CM_UYVY_PACKED,
61  YCbCr = IS_CM_CBYCRY_PACKED,
62  BGR5 = IS_CM_BGR5_PACKED,
63  BGR565 = IS_CM_BGR565_PACKED,
64  BGR8 = IS_CM_BGR8_PACKED,
65  BGRA8 = IS_CM_BGRA8_PACKED,
66  BGRY8 = IS_CM_BGRY8_PACKED,
67  RGB8 = IS_CM_RGB8_PACKED,
68  RGBA8 = IS_CM_RGBA8_PACKED,
69  RGBY8 = IS_CM_RGBY8_PACKED,
70 };
72 {
73  TRIGGER_OFF = IS_SET_TRIGGER_OFF,
74  TRIGGER_HI_LO = IS_SET_TRIGGER_HI_LO,
75  TRIGGER_LO_HI = IS_SET_TRIGGER_LO_HI,
76  TRIGGER_SOFTWARE = IS_SET_TRIGGER_SOFTWARE,
77  TRIGGER_HI_LO_SYNC = IS_SET_TRIGGER_HI_LO_SYNC,
78  TRIGGER_LO_HI_SYNC = IS_SET_TRIGGER_LO_HI_SYNC,
79 };
81 {
82  FLASH_OFF = IO_FLASH_MODE_OFF,
83  FLASH_TRIGGER_ACTIVE_LO = IO_FLASH_MODE_TRIGGER_LO_ACTIVE,
84  FLASH_TRIGGER_ACTIVE_HI = IO_FLASH_MODE_TRIGGER_HI_ACTIVE,
85  FLASH_CONSTANT_HIGH = IO_FLASH_MODE_CONSTANT_HIGH,
86  FLASH_CONSTANT_LOW = IO_FLASH_MODE_CONSTANT_LOW,
87  FLASH_FREERUN_ACTIVE_LO = IO_FLASH_MODE_FREERUN_LO_ACTIVE,
88  FLASH_FREERUN_ACTIVE_HI = IO_FLASH_MODE_FREERUN_HI_ACTIVE,
89 };
90 
91 class Camera
92 {
93 public:
94  Camera();
95  ~Camera();
96 
97  // Initialization functions in order they should be called.
98  static bool checkVersion(int &major, int &minor, int &build, const char *&expected);
99  int getNumberOfCameras() const;
100  unsigned int getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id);
101  bool openCameraCamId(unsigned int id);
102  bool openCameraDevId(unsigned int id);
103  bool openCameraSerNo(unsigned int serial_number);
104 
105  static const char* colorModeToString(uEyeColor mode);
106 
107  // Get Properties
108  const char * getCameraName() const { return cam_info_.strSensorName; }
109  unsigned int getCameraSerialNo() const { return serial_number_; }
110  int getWidthMax() const { return cam_info_.nMaxWidth; }
111  int getHeightMax() const { return cam_info_.nMaxHeight; }
112  int getWidth() const { return cam_info_.nMaxWidth / zoom_; }
113  int getHeight() const { return cam_info_.nMaxHeight / zoom_; }
114  int getZoom() const { return zoom_; }
115  uEyeColor getColorMode() const { return color_mode_; }
116  bool getAutoExposure() const { return auto_exposure_; }
117  double getExposure();
118  bool getHardwareGamma() const { return hardware_gamma_; }
119  int getPixelClock() const { return pixel_clock_; }
120  bool getGainBoost() const { return gain_boost_; }
121  bool getAutoGain() const { return auto_gain_; }
122  unsigned int getHardwareGain();
123  TriggerMode getTriggerMode();
124  TriggerMode getSupportedTriggers();
125 
126  // Set Properties
127  void setColorMode(uEyeColor mode);
128  void setAutoExposure(bool *enable);
129  void setExposure(double *time_ms);
130  void setHardwareGamma(bool *enable);
131  void setZoom(int *zoom);
132  void setPixelClock(int *MHz);
133  void setFrameRate(double *rate);
134  void setGainBoost(bool *enable);
135  void setAutoGain(bool *enable);
136  void setHardwareGain(int *gain);
137  bool setTriggerMode(TriggerMode mode);
138  void setFlashWithGlobalParams(FlashMode mode);
139  void setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec);
140  void setFlash(FlashMode mode);
141  void setTriggerDelay(int delay_usec);
142 
143  bool forceTrigger();
144 
145  typedef boost::function<void(const char *, size_t)> CamCaptureCB;
146  void startVideoCapture(CamCaptureCB);
147  void stopVideoCapture();
148 
149  void closeCamera();
150 
151 private:
152  inline void checkError(INT err) const {
153  INT err2 = IS_SUCCESS;
154  IS_CHAR* msg;
155  if (err != IS_SUCCESS) {
156  if (cam_ != 0) {
157  is_GetError(cam_, &err2, &msg);
158  if (err2 != IS_SUCCESS) {
159  throw ueye::uEyeException(err, msg);
160  }
161  } else {
162  throw ueye::uEyeException(err, "Camera failed to initialize");
163  }
164  }
165  }
166  void initPrivateVariables();
167  int getSubsampleParam(int *scale);
168  int getBinningParam(int *scale);
169  void flashUpdateGlobalParams();
170 
171  std::vector<char*> img_mem_;
172  std::vector<int> img_mem_id_;
173  void initMemoryPool(int size);
174  void destroyMemoryPool();
175  void captureThread(CamCaptureCB callback);
176  void restartVideoCapture();
177 
183  int zoom_;
187  double frame_rate_;
189  HIDS cam_;
190  SENSORINFO cam_info_;
191  unsigned int serial_number_;
192 
193  volatile bool streaming_;
194  volatile bool stop_capture_;
195  CamCaptureCB stream_callback_;
196  boost::thread thread_;
197 
198 };
199 } //namespace ueye
200 
201 #endif /* UEYE_CAMERA_H_ */
double frame_rate_
Definition: Camera.h:187
boost::function< void(const char *, size_t)> CamCaptureCB
Definition: Camera.h:145
Definition: Camera.h:44
bool getAutoGain() const
Definition: Camera.h:121
std::vector< char * > img_mem_
Definition: Camera.h:171
volatile bool stop_capture_
Definition: Camera.h:194
unsigned int getCameraSerialNo() const
Definition: Camera.h:109
int zoom_
Definition: Camera.h:183
int getWidthMax() const
Definition: Camera.h:110
bool flash_global_params_
Definition: Camera.h:188
bool auto_exposure_
Definition: Camera.h:179
const char * getCameraName() const
Definition: Camera.h:108
volatile bool streaming_
Definition: Camera.h:193
bool getGainBoost() const
Definition: Camera.h:120
SENSORINFO cam_info_
Definition: Camera.h:190
bool getAutoExposure() const
Definition: Camera.h:116
int getWidth() const
Definition: Camera.h:112
uEyeException(int code, const char *msg)
Definition: Camera.h:50
TriggerMode
Definition: Camera.h:71
int hardware_gain_
Definition: Camera.h:186
std::vector< int > img_mem_id_
Definition: Camera.h:172
bool gain_boost_
Definition: Camera.h:182
uEyeColor
Definition: Camera.h:56
int getPixelClock() const
Definition: Camera.h:119
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
FlashMode
Definition: Camera.h:80
bool auto_gain_
Definition: Camera.h:185
uEyeColor getColorMode() const
Definition: Camera.h:115
int getZoom() const
Definition: Camera.h:114
bool getHardwareGamma() const
Definition: Camera.h:118
void checkError(INT err) const
Definition: Camera.h:152
int getHeight() const
Definition: Camera.h:113
int pixel_clock_
Definition: Camera.h:184
unsigned int serial_number_
Definition: Camera.h:191
bool hardware_gamma_
Definition: Camera.h:181
CamCaptureCB stream_callback_
Definition: Camera.h:195
int getHeightMax() const
Definition: Camera.h:111


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