Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef UEYE_CAMERA_H_
00036 #define UEYE_CAMERA_H_
00037
00038 #include <ueye.h>
00039 #include <opencv/cv.h>
00040 #include <stdexcept>
00041 #include <string>
00042 #include <boost/function.hpp>
00043 #include <boost/thread.hpp>
00044
00045 namespace ueye
00046 {
00047
00048 struct uEyeException : public std::runtime_error
00049 {
00050 int error_code;
00051 uEyeException(int code, const char* msg) :
00052 std::runtime_error(msg), error_code(code)
00053 {
00054 }
00055 };
00056
00057 enum uEyeColor
00058 {
00059 MONO8 = IS_CM_MONO8,
00060 MONO16 = IS_CM_MONO16,
00061 YUV = IS_CM_UYVY_PACKED,
00062 YCbCr = IS_CM_CBYCRY_PACKED,
00063 BGR5 = IS_CM_BGR5_PACKED,
00064 BGR565 = IS_CM_BGR565_PACKED,
00065 BGR8 = IS_CM_BGR8_PACKED,
00066 BGRA8 = IS_CM_BGRA8_PACKED,
00067 BGRY8 = IS_CM_BGRY8_PACKED,
00068 RGB8 = IS_CM_RGB8_PACKED,
00069 RGBA8 = IS_CM_RGBA8_PACKED,
00070 RGBY8 = IS_CM_RGBY8_PACKED,
00071 };
00072 enum TriggerMode
00073 {
00074 TRIGGER_OFF = IS_SET_TRIGGER_OFF,
00075 TRIGGER_HI_LO = IS_SET_TRIGGER_HI_LO,
00076 TRIGGER_LO_HI = IS_SET_TRIGGER_LO_HI,
00077 TRIGGER_SOFTWARE = IS_SET_TRIGGER_SOFTWARE,
00078 TRIGGER_HI_LO_SYNC = IS_SET_TRIGGER_HI_LO_SYNC,
00079 TRIGGER_LO_HI_SYNC = IS_SET_TRIGGER_LO_HI_SYNC,
00080 };
00081 enum FlashMode
00082 {
00083 FLASH_OFF = IO_FLASH_MODE_OFF,
00084 FLASH_TRIGGER_ACTIVE_LO = IO_FLASH_MODE_TRIGGER_LO_ACTIVE,
00085 FLASH_TRIGGER_ACTIVE_HI = IO_FLASH_MODE_TRIGGER_HI_ACTIVE,
00086 FLASH_CONSTANT_HIGH = IO_FLASH_MODE_CONSTANT_HIGH,
00087 FLASH_CONSTANT_LOW = IO_FLASH_MODE_CONSTANT_LOW,
00088 FLASH_FREERUN_ACTIVE_LO = IO_FLASH_MODE_FREERUN_LO_ACTIVE,
00089 FLASH_FREERUN_ACTIVE_HI = IO_FLASH_MODE_FREERUN_HI_ACTIVE,
00090 };
00091
00092 class Camera
00093 {
00094 public:
00095 Camera();
00096 ~Camera();
00097
00098
00099 static bool checkVersion(int &major, int &minor, int &build, const char *&expected);
00100 int getNumberOfCameras() const;
00101 unsigned int getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id);
00102 bool openCameraCamId(unsigned int id);
00103 bool openCameraDevId(unsigned int id);
00104 bool openCameraSerNo(unsigned int serial_number);
00105
00106 static const char* colorModeToString(uEyeColor mode);
00107
00108
00109 const char * getCameraName() const;
00110 unsigned int getCameraSerialNo() const;
00111 int getWidthMax() const;
00112 int getHeightMax() const;
00113 int getWidth() const;
00114 int getHeight() const;
00115 int getZoom() const;
00116 uEyeColor getColorMode() const;
00117 bool getAutoExposure() const;
00118 double getExposure() const;
00119 bool getHardwareGamma() const;
00120 int getPixelClock() const;
00121 bool getGainBoost() const;
00122 bool getAutoGain() const;
00123 unsigned int getHardwareGain();
00124 TriggerMode getTriggerMode() const;
00125 TriggerMode getSupportedTriggers() const;
00126
00127
00128 void setColorMode(uEyeColor mode);
00129 void setAutoExposure(bool *enable);
00130 void setExposure(double *time_ms);
00131 void setHardwareGamma(bool *enable);
00132 void setZoom(int *zoom);
00133 void setPixelClock(int *MHz);
00134 void setFrameRate(double *rate);
00135 void setGainBoost(bool *enable);
00136 void setAutoGain(bool *enable);
00137 void setHardwareGain(int *gain);
00138 bool setTriggerMode(TriggerMode mode);
00139 void setFlashWithGlobalParams(FlashMode mode);
00140 void setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec);
00141 void setFlash(FlashMode mode);
00142 void setTriggerDelay(int delay_usec);
00143
00144 bool forceTrigger();
00145
00146 typedef boost::function<void(IplImage *)> CamCaptureCB;
00147 void startVideoCapture(CamCaptureCB);
00148 void stopVideoCapture();
00149
00150 void closeCamera();
00151
00152 private:
00153 inline void checkError(INT err) const;
00154 void initPrivateVariables();
00155 int getSubsampleParam(int *scale);
00156 int getBinningParam(int *scale);
00157 void flashUpdateGlobalParams();
00158
00159 std::vector<char*> img_mem_;
00160 std::vector<int> img_mem_id_;
00161 void initMemoryPool(int size);
00162 void destroyMemoryPool();
00163 void captureThread(CamCaptureCB callback);
00164 void restartVideoCapture();
00165
00166 uEyeColor color_mode_;
00167 bool auto_exposure_;
00168 double exposure_time_;
00169 bool hardware_gamma_;
00170 bool gain_boost_;
00171 int zoom_;
00172 int pixel_clock_;
00173 bool auto_gain_;
00174 int hardware_gain_;
00175 double frame_rate_;
00176 bool flash_global_params_;
00177 HIDS cam_;
00178 SENSORINFO cam_info_;
00179 unsigned int serial_number_;
00180
00181 bool streaming_;
00182 bool stop_capture_;
00183 CamCaptureCB stream_callback_;
00184 boost::thread thread_;
00185
00186 };
00187 }
00188
00189 #endif