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 <stdexcept>
00040 #include <string>
00041 #include <boost/function.hpp>
00042 #include <boost/thread.hpp>
00043
00044 namespace ueye
00045 {
00046
00047 struct uEyeException : public std::runtime_error
00048 {
00049 int error_code;
00050 uEyeException(int code, const char* msg) :
00051 std::runtime_error(msg), error_code(code)
00052 {
00053 }
00054 };
00055
00056 enum uEyeColor
00057 {
00058 MONO8 = IS_CM_MONO8,
00059 MONO16 = IS_CM_MONO16,
00060 YUV = IS_CM_UYVY_PACKED,
00061 YCbCr = IS_CM_CBYCRY_PACKED,
00062 BGR5 = IS_CM_BGR5_PACKED,
00063 BGR565 = IS_CM_BGR565_PACKED,
00064 BGR8 = IS_CM_BGR8_PACKED,
00065 BGRA8 = IS_CM_BGRA8_PACKED,
00066 BGRY8 = IS_CM_BGRY8_PACKED,
00067 RGB8 = IS_CM_RGB8_PACKED,
00068 RGBA8 = IS_CM_RGBA8_PACKED,
00069 RGBY8 = IS_CM_RGBY8_PACKED,
00070 };
00071 enum TriggerMode
00072 {
00073 TRIGGER_OFF = IS_SET_TRIGGER_OFF,
00074 TRIGGER_HI_LO = IS_SET_TRIGGER_HI_LO,
00075 TRIGGER_LO_HI = IS_SET_TRIGGER_LO_HI,
00076 TRIGGER_SOFTWARE = IS_SET_TRIGGER_SOFTWARE,
00077 TRIGGER_HI_LO_SYNC = IS_SET_TRIGGER_HI_LO_SYNC,
00078 TRIGGER_LO_HI_SYNC = IS_SET_TRIGGER_LO_HI_SYNC,
00079 };
00080 enum FlashMode
00081 {
00082 FLASH_OFF = IO_FLASH_MODE_OFF,
00083 FLASH_TRIGGER_ACTIVE_LO = IO_FLASH_MODE_TRIGGER_LO_ACTIVE,
00084 FLASH_TRIGGER_ACTIVE_HI = IO_FLASH_MODE_TRIGGER_HI_ACTIVE,
00085 FLASH_CONSTANT_HIGH = IO_FLASH_MODE_CONSTANT_HIGH,
00086 FLASH_CONSTANT_LOW = IO_FLASH_MODE_CONSTANT_LOW,
00087 FLASH_FREERUN_ACTIVE_LO = IO_FLASH_MODE_FREERUN_LO_ACTIVE,
00088 FLASH_FREERUN_ACTIVE_HI = IO_FLASH_MODE_FREERUN_HI_ACTIVE,
00089 };
00090
00091 class Camera
00092 {
00093 public:
00094 Camera();
00095 ~Camera();
00096
00097
00098 static bool checkVersion(int &major, int &minor, int &build, const char *&expected);
00099 int getNumberOfCameras() const;
00100 unsigned int getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id);
00101 bool openCameraCamId(unsigned int id);
00102 bool openCameraDevId(unsigned int id);
00103 bool openCameraSerNo(unsigned int serial_number);
00104
00105 static const char* colorModeToString(uEyeColor mode);
00106
00107
00108 const char * getCameraName() const { return cam_info_.strSensorName; }
00109 unsigned int getCameraSerialNo() const { return serial_number_; }
00110 int getWidthMax() const { return cam_info_.nMaxWidth; }
00111 int getHeightMax() const { return cam_info_.nMaxHeight; }
00112 int getWidth() const { return cam_info_.nMaxWidth / zoom_; }
00113 int getHeight() const { return cam_info_.nMaxHeight / zoom_; }
00114 int getZoom() const { return zoom_; }
00115 uEyeColor getColorMode() const { return color_mode_; }
00116 bool getAutoExposure() const { return auto_exposure_; }
00117 double getExposure();
00118 bool getHardwareGamma() const { return hardware_gamma_; }
00119 int getPixelClock() const { return pixel_clock_; }
00120 bool getGainBoost() const { return gain_boost_; }
00121 bool getAutoGain() const { return auto_gain_; }
00122 unsigned int getHardwareGain();
00123 TriggerMode getTriggerMode();
00124 TriggerMode getSupportedTriggers();
00125
00126
00127 void setColorMode(uEyeColor mode);
00128 void setAutoExposure(bool *enable);
00129 void setExposure(double *time_ms);
00130 void setHardwareGamma(bool *enable);
00131 void setZoom(int *zoom);
00132 void setPixelClock(int *MHz);
00133 void setFrameRate(double *rate);
00134 void setGainBoost(bool *enable);
00135 void setAutoGain(bool *enable);
00136 void setHardwareGain(int *gain);
00137 bool setTriggerMode(TriggerMode mode);
00138 void setFlashWithGlobalParams(FlashMode mode);
00139 void setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec);
00140 void setFlash(FlashMode mode);
00141 void setTriggerDelay(int delay_usec);
00142
00143 bool forceTrigger();
00144
00145 typedef boost::function<void(const char *, size_t)> CamCaptureCB;
00146 void startVideoCapture(CamCaptureCB);
00147 void stopVideoCapture();
00148
00149 void closeCamera();
00150
00151 private:
00152 inline void checkError(INT err) const {
00153 INT err2 = IS_SUCCESS;
00154 IS_CHAR* msg;
00155 if (err != IS_SUCCESS) {
00156 if (cam_ != 0) {
00157 is_GetError(cam_, &err2, &msg);
00158 if (err2 != IS_SUCCESS) {
00159 throw ueye::uEyeException(err, msg);
00160 }
00161 } else {
00162 throw ueye::uEyeException(err, "Camera failed to initialize");
00163 }
00164 }
00165 }
00166 void initPrivateVariables();
00167 int getSubsampleParam(int *scale);
00168 int getBinningParam(int *scale);
00169 void flashUpdateGlobalParams();
00170
00171 std::vector<char*> img_mem_;
00172 std::vector<int> img_mem_id_;
00173 void initMemoryPool(int size);
00174 void destroyMemoryPool();
00175 void captureThread(CamCaptureCB callback);
00176 void restartVideoCapture();
00177
00178 uEyeColor color_mode_;
00179 bool auto_exposure_;
00180 double exposure_time_;
00181 bool hardware_gamma_;
00182 bool gain_boost_;
00183 int zoom_;
00184 int pixel_clock_;
00185 bool auto_gain_;
00186 int hardware_gain_;
00187 double frame_rate_;
00188 bool flash_global_params_;
00189 HIDS cam_;
00190 SENSORINFO cam_info_;
00191 unsigned int serial_number_;
00192
00193 volatile bool streaming_;
00194 volatile bool stop_capture_;
00195 CamCaptureCB stream_callback_;
00196 boost::thread thread_;
00197
00198 };
00199 }
00200
00201 #endif