Camera.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Kevin Hallenbeck
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Kevin Hallenbeck nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
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 using namespace std;
00046 
00047 namespace ueye{
00048 
00049         struct uEyeException : public std::runtime_error
00050         {
00051                 int error_code;
00052                 uEyeException(int code, const char* msg)
00053                         : std::runtime_error(msg), error_code(code)
00054                 {}
00055         };
00056 
00057         enum uEyeColor{
00058                 RGB             = IS_CM_BGR8_PACKED,
00059                 YCbYCr  = IS_CM_CBYCRY_PACKED,
00060         };
00061         enum TriggerMode{
00062                 TRIGGER_OFF                     = IS_SET_TRIGGER_OFF,
00063                 TRIGGER_HI_LO           = IS_SET_TRIGGER_HI_LO,
00064                 TRIGGER_LO_HI           = IS_SET_TRIGGER_LO_HI,
00065                 TRIGGER_SOFTWARE        = IS_SET_TRIGGER_SOFTWARE,
00066                 TRIGGER_HI_LO_SYNC      = IS_SET_TRIGGER_HI_LO_SYNC,
00067                 TRIGGER_LO_HI_SYNC      = IS_SET_TRIGGER_LO_HI_SYNC,
00068         };
00069         enum FlashMode{
00070                 FLASH_OFF                               = IO_FLASH_MODE_OFF,
00071                 FLASH_TRIGGER_ACTIVE_LO = IO_FLASH_MODE_TRIGGER_LO_ACTIVE,
00072                 FLASH_TRIGGER_ACTIVE_HI = IO_FLASH_MODE_TRIGGER_HI_ACTIVE,
00073                 FLASH_CONSTANT_HIGH             = IO_FLASH_MODE_CONSTANT_HIGH,
00074                 FLASH_CONSTANT_LOW              = IO_FLASH_MODE_CONSTANT_LOW,
00075                 FLASH_FREERUN_ACTIVE_LO = IO_FLASH_MODE_FREERUN_LO_ACTIVE,
00076                 FLASH_FREERUN_ACTIVE_HI = IO_FLASH_MODE_FREERUN_HI_ACTIVE,
00077         };
00078 
00079         class Camera
00080         {
00081         public:
00082                 Camera();
00083                 ~Camera();
00084 
00085                 // Initialization functions in order they should be called.
00086                 bool checkVersion(int &Major, int &Minor, int &Build, char *&Expected);
00087                 int getNumberOfCameras();
00088                 unsigned int getSerialNumberList(vector<unsigned int>& SerNo, vector<unsigned int>& DevId);
00089                 bool openCameraCamId(unsigned int id);
00090                 bool openCameraDevId(unsigned int id);
00091                 bool openCameraSerNo(unsigned int serial_number);
00092 
00093                 // Get Properties
00094                 char * getCameraName();
00095                 unsigned int getCameraSerialNo();
00096                 int getWidthMax();
00097                 int getHeightMax();
00098                 int getWidth();
00099                 int getHeight();
00100                 int getZoom();
00101                 bool getAutoExposure();
00102                 double getExposure();
00103                 bool getHardwareGamma();
00104                 int getPixelClock();
00105                 bool getGainBoost();
00106                 bool getAutoGain();
00107                 unsigned int getHardwareGain();
00108                 TriggerMode getTriggerMode();
00109                 TriggerMode getSupportedTriggers();
00110 
00111                 // Set Properties
00112                 void setColorMode(uEyeColor mode);
00113                 void setAutoExposure(bool *Enable);
00114                 void setExposure(double *time_ms);
00115                 void setHardwareGamma(bool *Enable);
00116                 void setZoom(int *zoom);
00117                 void setPixelClock(int *MHz);
00118                 void setFrameRate(double *rate);
00119                 void setGainBoost(bool *Enable);
00120                 void setAutoGain(bool *Enable);
00121                 void setHardwareGain(int *gain);
00122                 bool setTriggerMode(TriggerMode mode);
00123                 void setFlashWithGlobalParams(FlashMode mode);
00124                 void setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec);
00125                 void setFlash(FlashMode mode);
00126                 void setTriggerDelay(int delay_usec);
00127 
00128                 bool forceTrigger();
00129 
00130                 typedef boost::function<void (IplImage *)> camCaptureCB;
00131                 void startVideoCapture(camCaptureCB);
00132                 void stopVideoCapture();
00133 
00134                 void closeCamera();
00135 
00136         private:
00137                 void CheckError(INT err);
00138                 void InitPrivateVariables();
00139                 int getSubsampleParam(int *scale);
00140                 int getBinningParam(int *scale);
00141                 void flashUpdateGlobalParams();
00142 
00143                 char **imgMem_;
00144                 int  *imgMemId_;
00145                 int NumBuffers_;
00146                 void initMemoryPool(int size);
00147                 void destroyMemoryPool();
00148                 void captureThread(camCaptureCB captureCallback);
00149                 void restartVideoCapture();
00150 
00151                 uEyeColor ColorMode_;
00152                 bool AutoExposure_;
00153                 double ExposureTime_;
00154                 bool HardwareGamma_;
00155                 bool GainBoost_;
00156                 int Zoom_;
00157                 int PixelClock_;
00158                 bool AutoGain_;
00159                 int HardwareGain_;
00160                 double FrameRate_;
00161                 bool FlashGlobalParams_;
00162                 HIDS hCam_;
00163                 SENSORINFO camInfo_;
00164                 unsigned int serialNo_;
00165 
00166                 bool Streaming_;
00167                 bool StopCapture_;
00168                 camCaptureCB StreamCallback_;
00169                 boost::thread VidThread_;
00170 
00171         };
00172 }//namespace ueye
00173 
00174 #endif /* UEYE_CAMERA_H_ */


ueye
Author(s): Kevin Hallenbeck
autogenerated on Tue Jan 7 2014 11:40:31