Camera.cpp
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 #include "ueye/Camera.h"
00036 
00037 using namespace std;
00038 
00039 #define DEBUG_ERROR_CHECKS 0
00040 
00041 #if DEBUG_ERROR_CHECKS
00042 #define CHECK_ERR       CheckError
00043 #else
00044 #define CHECK_ERR(fnc)                                                  \
00045 do {                                                            \
00046         IS_CHAR* msg;                                                                                   \
00047         int err = fnc;                                          \
00048         if (err != IS_SUCCESS) {                                                                \
00049                 if (hCam_ != 0){                                                                        \
00050                         is_GetError(hCam_, &err, &msg);                                 \
00051                         if(err != IS_SUCCESS){                                                  \
00052                                 throw uEyeException(err, msg);                          \
00053                         }                                                                                               \
00054                 }else{                                                                                          \
00055                         throw uEyeException(err, "Camera failed to initialize");\
00056                 }                                                                                                       \
00057         }                                                       \
00058 } while (false)
00059 #endif
00060 
00061 namespace ueye{
00062 
00063 void Camera::CheckError(INT err)
00064 {
00065         INT err2 = IS_SUCCESS;
00066         IS_CHAR* msg;
00067         if (err != IS_SUCCESS) {
00068                 if (hCam_ != 0){
00069                         is_GetError(hCam_, &err2, &msg);
00070                         if(err2 != IS_SUCCESS){
00071                                 throw ueye::uEyeException(err, msg);
00072                         }
00073                 }else{
00074                         throw ueye::uEyeException(err, "Camera failed to initialize");
00075                 }
00076         }
00077 }
00078 
00079 void Camera::InitPrivateVariables()
00080 {
00081         Streaming_ = false;
00082         StopCapture_ = false;
00083         ColorMode_ = RGB;
00084         AutoExposure_ = false;
00085         ExposureTime_ = 99.0;
00086         HardwareGamma_ = true;
00087         GainBoost_ = false;
00088         Zoom_ = 1;
00089         PixelClock_ = 20;
00090         AutoGain_ = false;
00091         HardwareGain_ = 100;
00092         FrameRate_ = 5.0;
00093         FlashGlobalParams_ = false;
00094         serialNo_ = 0;
00095         hCam_ = 0;
00096         memset(&camInfo_, 0x00, sizeof(camInfo_));
00097         NumBuffers_ = 0;
00098         StreamCallback_ = NULL;
00099 }
00100 
00101 Camera::Camera()
00102 {
00103         InitPrivateVariables();
00104 }
00105 
00106 bool Camera::checkVersion(int &Major, int &Minor, int &Build, char *&Expected)
00107 {
00108         Expected = (char*)"4.20.6";
00109         Build = is_GetDLLVersion();
00110         Major = (Build >> 24) & 0x000000FF;
00111         Minor = (Build >> 16) & 0x000000FF;
00112         Build &= 0x0000FFFF;
00113         if((Major == 4) && (Minor == 20) && (Build == 6)){
00114                 return true;
00115         }
00116         return false;
00117 }
00118 
00119 int Camera::getNumberOfCameras()
00120 {
00121         int Num = 0;
00122         CHECK_ERR(is_GetNumberOfCameras(&Num));
00123         return Num;
00124 }
00125 
00126 
00127 unsigned int Camera::getSerialNumberList(vector<unsigned int>& SerNo, vector<unsigned int>& DevId)
00128 {
00129         int num = getNumberOfCameras();
00130         if( num > 0 ) {
00131                 UEYE_CAMERA_LIST *list = (UEYE_CAMERA_LIST *)malloc(sizeof(DWORD) + num*sizeof(UEYE_CAMERA_INFO));
00132                 list->dwCount = num;
00133                 if (is_GetCameraList(list) == IS_SUCCESS){
00134                         num = list->dwCount;
00135                         SerNo.resize(num);
00136                         DevId.resize(num);
00137                         for(int i=0; i<num; i++){
00138                                 SerNo[i] = atoi(list->uci[i].SerNo);
00139                                 DevId[i] = list->uci[i].dwDeviceID;
00140                         }
00141                 }else{
00142                         num = 0;
00143                 }
00144                 free(list);
00145                 return num;
00146         }
00147         return 0;
00148 }
00149 
00150 bool Camera::openCameraCamId(unsigned int id)
00151 {
00152         if(getNumberOfCameras() < 1){
00153                 return false;
00154         }
00155 
00156         hCam_ = id;
00157         CHECK_ERR(is_InitCamera(&hCam_, 0));
00158 
00159         CHECK_ERR(is_GetSensorInfo(hCam_, &camInfo_));
00160         CAMINFO info;
00161         CHECK_ERR(is_GetCameraInfo(hCam_, &info));
00162         serialNo_ = atoi(info.SerNo);
00163 
00164         setColorMode(ColorMode_);
00165         setAutoExposure(&AutoExposure_);
00166         if(!AutoExposure_){
00167                 setExposure(&ExposureTime_);
00168         }
00169         setHardwareGamma(&HardwareGamma_);
00170         setGainBoost(&GainBoost_);
00171         setAutoGain(&AutoGain_);
00172         if(!AutoGain_){
00173                 setHardwareGain(&HardwareGain_);
00174         }
00175         setZoom(&Zoom_);
00176         setPixelClock(&PixelClock_);
00177         setFrameRate(&FrameRate_);
00178         return true;
00179 }
00180 bool Camera::openCameraDevId(unsigned int id)
00181 {
00182         return openCameraCamId(id | IS_USE_DEVICE_ID);
00183 }
00184 bool Camera::openCameraSerNo(unsigned int serial_number)
00185 {
00186         vector<unsigned int> SerNo;
00187         vector<unsigned int> DevId;
00188         unsigned int num = getSerialNumberList(SerNo, DevId);
00189         for(unsigned int i=0; i<num; i++){
00190                 if(SerNo[i] == serial_number){
00191                         return openCameraDevId(DevId[i]);
00192                 }
00193         }
00194         return false;
00195 }
00196 
00197 char * Camera::getCameraName()
00198 {
00199         return camInfo_.strSensorName;
00200 }
00201 unsigned int Camera::getCameraSerialNo(){
00202         return serialNo_;
00203 }
00204 int Camera::getZoom()
00205 {
00206         return Zoom_;
00207 }
00208 int Camera::getWidthMax()
00209 {
00210         return camInfo_.nMaxWidth;
00211 }
00212 int Camera::getHeightMax()
00213 {
00214         return camInfo_.nMaxHeight;
00215 }
00216 int Camera::getWidth()
00217 {
00218         return camInfo_.nMaxWidth / Zoom_;
00219 }
00220 int Camera::getHeight()
00221 {
00222         return camInfo_.nMaxHeight / Zoom_;
00223 }
00224 bool Camera::getAutoExposure()
00225 {
00226         return AutoExposure_;
00227 }
00228 double Camera::getExposure()
00229 {
00230         double time_ms;
00231         CHECK_ERR(is_Exposure (hCam_, IS_EXPOSURE_CMD_GET_EXPOSURE, &time_ms, sizeof(double)));
00232         return time_ms;
00233 }
00234 bool Camera::getHardwareGamma()
00235 {
00236         return HardwareGamma_;
00237 }
00238 int Camera::getPixelClock()
00239 {
00240         return PixelClock_;
00241 }
00242 bool Camera::getGainBoost()
00243 {
00244         return GainBoost_;
00245 }
00246 bool Camera::getAutoGain()
00247 {
00248         return AutoGain_;
00249 }
00250 unsigned int Camera::getHardwareGain()
00251 {
00252         HardwareGain_ = is_SetHWGainFactor(hCam_, IS_GET_MASTER_GAIN_FACTOR, 0);
00253         return HardwareGain_;
00254 }
00255 TriggerMode Camera::getTriggerMode()
00256 {
00257         return (TriggerMode)is_SetExternalTrigger(hCam_, IS_GET_EXTERNALTRIGGER);
00258 }
00259 TriggerMode Camera::getSupportedTriggers()
00260 {
00261         return (TriggerMode)is_SetExternalTrigger(hCam_, IS_GET_SUPPORTED_TRIGGER_MODE);
00262 }
00263 
00264 void Camera::setColorMode(uEyeColor mode)
00265 {
00266         CHECK_ERR(is_SetColorMode(hCam_, mode));
00267         ColorMode_ = mode;
00268 }
00269 void Camera::setAutoExposure(bool *Enable)
00270 {
00271         double param1 = *Enable ? 1.0 : 0.0;
00272         double param2 = 0;
00273         if(IS_SUCCESS != is_SetAutoParameter(hCam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2)){
00274                 param1 = 0;
00275                 is_SetAutoParameter(hCam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2);
00276                 *Enable = false;
00277         }
00278         AutoExposure_ = *Enable;
00279 }
00280 void  Camera::setExposure(double *time_ms)
00281 {
00282         bool b = false;
00283         setAutoExposure(&b);
00284         CHECK_ERR(is_Exposure (hCam_, IS_EXPOSURE_CMD_SET_EXPOSURE, time_ms, sizeof(double)));
00285         flashUpdateGlobalParams();
00286         ExposureTime_ = *time_ms;
00287 }
00288 void Camera::setHardwareGamma(bool *Enable)
00289 {
00290         if(*Enable){
00291                 if(IS_SUCCESS != is_SetHardwareGamma(hCam_, IS_SET_HW_GAMMA_ON)){
00292                         is_SetHardwareGamma(hCam_, IS_SET_HW_GAMMA_OFF);
00293                         *Enable = false;
00294                 }
00295         }else{
00296                 is_SetHardwareGamma(hCam_, IS_SET_HW_GAMMA_OFF);
00297         }
00298         HardwareGamma_ = *Enable;
00299 }
00300 void Camera::setZoom(int *zoom)
00301 {
00302         if(Zoom_ != *zoom){
00303                 // Reset zoom
00304                 is_SetSubSampling(hCam_, 0);
00305                 is_SetBinning(hCam_, 0);
00306 
00307                 // Try Subsampling then Binning
00308                 if(IS_SUCCESS != is_SetSubSampling(hCam_, getSubsampleParam(zoom))){
00309                         is_SetSubSampling(hCam_, 0);
00310                         if(IS_SUCCESS != is_SetBinning(hCam_, getBinningParam(zoom))){
00311                                 is_SetBinning(hCam_, 0);
00312                                 *zoom = 1;
00313                         }
00314                 }
00315 
00316                 // Zoom affects the frame-rate and needs a restart to change the buffer sizes
00317                 is_HotPixel(hCam_, IS_HOTPIXEL_ENABLE_CAMERA_CORRECTION, NULL, 0);
00318                 setFrameRate(&FrameRate_);
00319                 restartVideoCapture();
00320         }
00321         Zoom_ = *zoom;
00322 }
00323 void Camera::setPixelClock(int *MHz)
00324 {
00325         int Ranges[3];
00326         memset(Ranges, 0x00, sizeof(Ranges));
00327 
00328         // Sanitize to increment, minimum, and maximum
00329         CHECK_ERR(is_PixelClock(hCam_, IS_PIXELCLOCK_CMD_GET_RANGE, Ranges, sizeof(Ranges)));
00330         if(Ranges[2] > 1){
00331                 if((*MHz - Ranges[0]) % Ranges[2] != 0){
00332                         *MHz -= (*MHz - Ranges[0]) % Ranges[2];
00333                 }
00334         }
00335         if(*MHz < Ranges[0]){
00336                 *MHz = Ranges[0];
00337         }
00338         if(*MHz > Ranges[1]){
00339                 *MHz = Ranges[1];
00340         }
00341 
00342         CHECK_ERR(is_PixelClock(hCam_, IS_PIXELCLOCK_CMD_SET, MHz, sizeof(int)));
00343         setFrameRate(&FrameRate_);
00344 
00345         PixelClock_ = *MHz;
00346 }
00347 void Camera::setFrameRate(double *rate)
00348 {
00349         CHECK_ERR(is_SetFrameRate(hCam_, *rate, rate));
00350         flashUpdateGlobalParams();
00351         FrameRate_ = *rate;
00352 }
00353 void Camera::setGainBoost(bool *enable)
00354 {
00355         if(is_SetGainBoost(hCam_, IS_GET_SUPPORTED_GAINBOOST) == IS_SET_GAINBOOST_ON){
00356                 if(*enable)
00357                         is_SetGainBoost(hCam_, IS_SET_GAINBOOST_ON);
00358                 else
00359                         is_SetGainBoost(hCam_, IS_SET_GAINBOOST_OFF);
00360                 GainBoost_ = is_SetGainBoost(hCam_, IS_GET_GAINBOOST) == IS_SET_GAINBOOST_ON;
00361         }else{
00362                 GainBoost_ = false;
00363         }
00364         *enable = GainBoost_;
00365 }
00366 void Camera::setAutoGain(bool *Enable)
00367 {
00368         double param1 = *Enable ? 1.0 : 0.0;
00369         double param2 = 0;
00370         if(IS_SUCCESS != is_SetAutoParameter(hCam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2)){
00371                 param1 = 0;
00372                 is_SetAutoParameter(hCam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2);
00373                 *Enable = false;
00374         }
00375         AutoGain_ = *Enable;
00376 }
00377 void Camera::setHardwareGain(int *gain)
00378 {
00379         bool b = false;
00380         setAutoGain(&b);
00381         if(*gain < 0)
00382                 *gain = 0;
00383         if(*gain > 400)
00384                 *gain = 400;
00385         HardwareGain_ = is_SetHWGainFactor(hCam_, IS_SET_MASTER_GAIN_FACTOR, *gain);
00386         *gain = HardwareGain_;
00387 }
00388 bool Camera::setTriggerMode(TriggerMode mode)
00389 {
00390         if((mode == 0) || (mode & getSupportedTriggers())){
00391                 if(is_SetExternalTrigger(hCam_, mode) == IS_SUCCESS){
00392                         return true;
00393                 }
00394         }
00395         return false;
00396 }
00397 void Camera::setFlashWithGlobalParams(FlashMode mode)
00398 {
00399         UINT nMode = mode;
00400         switch(mode)
00401         {
00402         case FLASH_FREERUN_ACTIVE_LO:
00403         case FLASH_FREERUN_ACTIVE_HI:
00404         case FLASH_TRIGGER_ACTIVE_LO:
00405         case FLASH_TRIGGER_ACTIVE_HI:
00406                 FlashGlobalParams_ = true;
00407                 break;
00408 
00409         case FLASH_CONSTANT_HIGH:
00410         case FLASH_CONSTANT_LOW:
00411                 FlashGlobalParams_ = false;
00412                 break;
00413 
00414         case FLASH_OFF:
00415         default:
00416                 FlashGlobalParams_ = false;
00417                 nMode = FLASH_OFF;
00418                 break;
00419         }
00420         CHECK_ERR(is_IO(hCam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&nMode, sizeof(nMode)));
00421         flashUpdateGlobalParams();
00422 }
00423 void Camera::setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec)
00424 {
00425         int num_mode = int(mode);
00426 
00427         CHECK_ERR(is_IO(hCam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&num_mode, sizeof(num_mode)));
00428 
00429         if (mode != FLASH_OFF)
00430         {
00431                 IO_FLASH_PARAMS params;
00432                 memset(&params, 0, sizeof(params));
00433 
00434                 params.s32Delay = delay_usec;
00435                 params.u32Duration = duration_usec;
00436 
00437                 CHECK_ERR(is_IO(hCam_, IS_IO_CMD_FLASH_SET_PARAMS, &params, sizeof(params)));
00438         }
00439 
00440         FlashGlobalParams_ = false;
00441 }
00442 void Camera::setFlash(FlashMode mode)
00443 {
00444         // If flash delay = 0 and flash duration = 0, the flash signal is
00445         // automatically synchronized to the exposure time.
00446         setFlash(mode, 0, 0);
00447 }
00448 void Camera::flashUpdateGlobalParams()
00449 {
00450         if(FlashGlobalParams_){
00451                 IO_FLASH_PARAMS params;
00452                 CHECK_ERR(is_IO(hCam_, IS_IO_CMD_FLASH_GET_GLOBAL_PARAMS,
00453                                 (void*)&params, sizeof(params)));
00454                 CHECK_ERR(is_IO(hCam_, IS_IO_CMD_FLASH_APPLY_GLOBAL_PARAMS, NULL, 0));
00455         }
00456 }
00457 void Camera::setTriggerDelay(int delay_usec)
00458 {
00459         CHECK_ERR(is_SetTriggerDelay(hCam_, delay_usec));
00460 }
00461 
00462 bool Camera::forceTrigger()
00463 {
00464         if(Streaming_)
00465                 return is_ForceTrigger(hCam_) == IS_SUCCESS;
00466         return false;
00467 }
00468 
00469 int Camera::getSubsampleParam(int *scale)
00470 {
00471         int param;
00472         if(*scale == 3){
00473                 *scale = 2;
00474         }
00475         switch(*scale){
00476                 case 2:
00477                         param = IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL;
00478                         break;
00479                 case 4:
00480                         param = IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL;
00481                         break;
00482                 default:
00483                         *scale = 1;
00484                         param = IS_SUBSAMPLING_DISABLE;
00485                         break;
00486         }
00487         return param;
00488 }
00489 int Camera::getBinningParam(int *scale)
00490 {
00491         int param;
00492         if(*scale == 3){
00493                 *scale = 2;
00494         }
00495         switch(*scale){
00496                 case 2:
00497                         param = IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL;
00498                         break;
00499                 case 4:
00500                         param = IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL;
00501                         break;
00502                 default:
00503                         *scale = 1;
00504                         param = IS_BINNING_DISABLE;
00505                         break;
00506         }
00507         return param;
00508 }
00509 
00510 void Camera::closeCamera(){
00511         if(hCam_ > 0){
00512                 // Release camera and all associated memory
00513                 CHECK_ERR(IS_SUCCESS != is_ExitCamera(hCam_));
00514                 InitPrivateVariables();
00515         }
00516 }
00517 
00518 Camera::~Camera(){
00519         closeCamera();
00520 }
00521 
00522 void Camera::initMemoryPool(int size)
00523 {
00524         int Width = getWidth();
00525         int Height = getHeight();
00526         if(size < 2){
00527                 size = 2;
00528         }
00529         imgMem_ = new char* [size];
00530         imgMemId_ = new int [size];
00531         for (int i = 0; i < size; i++){
00532                 if (IS_SUCCESS != is_AllocImageMem (hCam_, Width, Height, 24, &imgMem_[i], &imgMemId_[i])){
00533                         throw uEyeException(-1, "Failed to initialize memory.");
00534                 }
00535                 //add memory to memory pool
00536                 if (IS_SUCCESS != is_SetImageMem(hCam_, imgMem_[i], imgMemId_[i])){
00537                         throw uEyeException(-1, "Failed to initialize memory.");
00538                 }
00539         }
00540         NumBuffers_ = size;
00541 }
00542 void Camera::destroyMemoryPool()
00543 {
00544         for (int i=0; i<NumBuffers_; i++){
00545                 CHECK_ERR(is_FreeImageMem(hCam_,  imgMem_[i], imgMemId_[i]));
00546         }
00547         NumBuffers_ = 0;
00548 }
00549 
00550 void Camera::captureThread(camCaptureCB callback)
00551 {
00552         Streaming_ = true;
00553         void * imgMem;
00554         StopCapture_ = false;
00555 
00556         initMemoryPool(4);
00557 
00558         // Setup video event
00559         CHECK_ERR(is_EnableEvent(hCam_, IS_SET_EVENT_FRAME));
00560         CHECK_ERR(is_CaptureVideo(hCam_, IS_WAIT));
00561         IplImage * p_img = cvCreateImageHeader(cvSize(getWidth(),getHeight()), IPL_DEPTH_8U, 3);
00562 
00563         while(!StopCapture_){
00564                 // Wait for image. Timeout after 2*FramePeriod = (2000ms/FrameRate)
00565                 if(is_WaitEvent(hCam_, IS_SET_EVENT_FRAME, (int)(2000/FrameRate_)) == IS_SUCCESS){
00566                         if(is_GetImageMem(hCam_, &imgMem) == IS_SUCCESS){
00567                                 p_img->imageData = (char*)imgMem;
00568                                 callback(p_img);
00569                         }
00570                 }
00571         }
00572 
00573         // Stop video event
00574         CHECK_ERR(is_DisableEvent(hCam_, IS_SET_EVENT_FRAME));
00575         CHECK_ERR(is_StopLiveVideo(hCam_, IS_WAIT));
00576 
00577         destroyMemoryPool();
00578         Streaming_ = false;
00579 }
00580 
00581 void Camera::startVideoCapture(camCaptureCB callback){
00582         StreamCallback_ = callback;
00583         VidThread_ = boost::thread(&Camera::captureThread, this, callback);
00584 }
00585 void Camera::stopVideoCapture(){
00586         StopCapture_ = true;
00587         if (VidThread_.joinable()){
00588                 forceTrigger();
00589                 VidThread_.join();
00590         }
00591 }
00592 void Camera::restartVideoCapture(){
00593         if(Streaming_){
00594                 if(StreamCallback_ != NULL){
00595                         stopVideoCapture();
00596                         startVideoCapture(StreamCallback_);
00597                 }
00598         }
00599 }
00600 
00601 }//namespace ueye


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