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 // Check expected uEye SDK version in ueye.h for supported architectures
00038 #if defined(__i386) || defined(__i386__) || defined(_M_IX86)
00039   #define EXPECTED_VERSION_MAJOR 4
00040   #define EXPECTED_VERSION_MINOR 40
00041   #define EXPECTED_VERSION_BUILD 19
00042   #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00043   #warning Expected ueye driver version 4.40.x. Different version found in ueye.h.
00044   #endif
00045 #elif defined(__x86_64) || defined(__x86_64__) || defined(__amd64) || defined(_M_X64)
00046   #define EXPECTED_VERSION_MAJOR 4
00047   #define EXPECTED_VERSION_MINOR 40
00048   #define EXPECTED_VERSION_BUILD 19
00049   #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00050   #warning Expected ueye driver version 4.40.x. Different version found in ueye.h.
00051   #endif
00052 #elif defined(__arm__) || defined(__TARGET_ARCH_ARM)
00053   #define EXPECTED_VERSION_MAJOR 4
00054   #define EXPECTED_VERSION_MINOR 30
00055   #define EXPECTED_VERSION_BUILD 18
00056   #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00057   #warning Expected ueye driver version 4.30.x. Different version found in ueye.h.
00058   #endif
00059 #elif defined(__ia64) || defined(__ia64__) || defined(_M_IA64)
00060   #define EXPECTED_VERSION_MAJOR 0
00061   #define EXPECTED_VERSION_MINOR 0
00062   #define EXPECTED_VERSION_BUILD 0
00063   #warning Architecture ia64 not explicitly supported.
00064 #elif defined(__ppc__) || defined(__ppc) || defined(__powerpc__) || defined(_ARCH_COM) || defined(_ARCH_PWR) || defined(_ARCH_PPC) || defined(_M_MPPC) || defined(_M_PPC)
00065   #define EXPECTED_VERSION_MAJOR 0
00066   #define EXPECTED_VERSION_MINOR 0
00067   #define EXPECTED_VERSION_BUILD 0
00068   #warning Architecture ppc not explicitly supported.
00069 #else
00070   #define EXPECTED_VERSION_MAJOR 0
00071   #define EXPECTED_VERSION_MINOR 0
00072   #define EXPECTED_VERSION_BUILD 0
00073   #warning Architecture not explicitly supported. Supported: amd64, i386, arm.
00074 #endif
00075 
00076 
00077 namespace ueye
00078 {
00079 
00080 void Camera::checkError(INT err) const
00081 {
00082   INT err2 = IS_SUCCESS;
00083   IS_CHAR* msg;
00084   if (err != IS_SUCCESS) {
00085     if (cam_ != 0) {
00086       is_GetError(cam_, &err2, &msg);
00087       if (err2 != IS_SUCCESS) {
00088         throw ueye::uEyeException(err, msg);
00089       }
00090     } else {
00091       throw ueye::uEyeException(err, "Camera failed to initialize");
00092     }
00093   }
00094 }
00095 
00096 void Camera::initPrivateVariables()
00097 {
00098   streaming_ = false;
00099   stop_capture_ = false;
00100   color_mode_ = MONO8;
00101   auto_exposure_ = false;
00102   exposure_time_ = 99.0;
00103   hardware_gamma_ = true;
00104   gain_boost_ = false;
00105   zoom_ = 1;
00106   pixel_clock_ = 20;
00107   auto_gain_ = false;
00108   hardware_gain_ = 100;
00109   frame_rate_ = 5.0;
00110   flash_global_params_ = false;
00111   serial_number_ = 0;
00112   cam_ = 0;
00113   memset(&cam_info_, 0x00, sizeof(cam_info_));
00114   stream_callback_ = NULL;
00115 }
00116 
00117 Camera::Camera()
00118 {
00119   initPrivateVariables();
00120 }
00121 
00122 #define STR_HELPER(x) #x
00123 #define STR(x) STR_HELPER(x)
00124 bool Camera::checkVersion(int &major, int &minor, int &build, const char *&expected)
00125 {
00126   expected = STR(EXPECTED_VERSION_MAJOR) "." STR(EXPECTED_VERSION_MINOR) "." STR(EXPECTED_VERSION_BUILD);
00127   build = is_GetDLLVersion();
00128   major = (build >> 24) & 0x000000FF;
00129   minor = (build >> 16) & 0x000000FF;
00130   build &= 0x0000FFFF;
00131   if ((major == EXPECTED_VERSION_MAJOR) && (minor == EXPECTED_VERSION_MINOR) && (build == EXPECTED_VERSION_BUILD)) {
00132     return true;
00133   }
00134   return false;
00135 }
00136 #undef STR_HELPER
00137 #undef STR
00138 
00139 int Camera::getNumberOfCameras() const
00140 {
00141   int num = 0;
00142   checkError(is_GetNumberOfCameras(&num));
00143   return num;
00144 }
00145 
00146 unsigned int Camera::getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id)
00147 {
00148   int num = getNumberOfCameras();
00149   if (num > 0) {
00150     UEYE_CAMERA_LIST *list = (UEYE_CAMERA_LIST *)malloc(sizeof(DWORD) + num * sizeof(UEYE_CAMERA_INFO));
00151     list->dwCount = num;
00152     if (is_GetCameraList(list) == IS_SUCCESS) {
00153       num = list->dwCount;
00154       serial.resize(num);
00155       dev_id.resize(num);
00156       for (int i = 0; i < num; i++) {
00157         serial[i] = atoll(list->uci[i].SerNo);
00158         dev_id[i] = list->uci[i].dwDeviceID;
00159       }
00160     } else {
00161       num = 0;
00162     }
00163     free(list);
00164     return num;
00165   }
00166   return 0;
00167 }
00168 
00169 bool Camera::openCameraCamId(unsigned int id)
00170 {
00171   if (getNumberOfCameras() < 1) {
00172     return false;
00173   }
00174 
00175   cam_ = id;
00176   checkError(is_InitCamera(&cam_, 0));
00177 
00178   checkError(is_GetSensorInfo(cam_, &cam_info_));
00179   CAMINFO info;
00180   checkError(is_GetCameraInfo(cam_, &info));
00181   serial_number_ = atoll(info.SerNo);
00182 
00183   setColorMode(color_mode_);
00184   setAutoExposure(&auto_exposure_);
00185   if (!auto_exposure_) {
00186     setExposure(&exposure_time_);
00187   }
00188   setHardwareGamma(&hardware_gamma_);
00189   setGainBoost(&gain_boost_);
00190   setAutoGain(&auto_gain_);
00191   if (!auto_gain_) {
00192     setHardwareGain(&hardware_gain_);
00193   }
00194   setZoom(&zoom_);
00195   setPixelClock(&pixel_clock_);
00196   setFrameRate(&frame_rate_);
00197   return true;
00198 }
00199 bool Camera::openCameraDevId(unsigned int id)
00200 {
00201   return openCameraCamId(id | IS_USE_DEVICE_ID);
00202 }
00203 bool Camera::openCameraSerNo(unsigned int serial_number)
00204 {
00205   std::vector<unsigned int> serial;
00206   std::vector<unsigned int> dev_id;
00207   unsigned int num = getSerialNumberList(serial, dev_id);
00208   for (unsigned int i = 0; i < num; i++) {
00209     if (serial[i] == serial_number) {
00210       return openCameraDevId(dev_id[i]);
00211     }
00212   }
00213   return false;
00214 }
00215 
00216 const char* Camera::colorModeToString(uEyeColor mode)
00217 {
00218   switch (mode) {
00219     case MONO8:
00220       return "mono8";
00221     case MONO16:
00222       return "mono16";
00223     case BGR5:
00224       return "bgr5";
00225     case BGR565:
00226       return "bgr565";
00227     case YUV:
00228       return "yuv422";
00229     case YCbCr:
00230       return "ycbcr422";
00231     case BGR8:
00232       return "bgr8";
00233     case RGB8:
00234       return "rgb8";
00235     case BGRA8:
00236     case BGRY8:
00237       return "bgra8";
00238     case RGBA8:
00239     case RGBY8:
00240       return "rgba8";
00241   }
00242   return "";
00243 }
00244 
00245 const char * Camera::getCameraName() const
00246 {
00247   return cam_info_.strSensorName;
00248 }
00249 unsigned int Camera::getCameraSerialNo() const
00250 {
00251   return serial_number_;
00252 }
00253 int Camera::getZoom() const
00254 {
00255   return zoom_;
00256 }
00257 int Camera::getWidthMax() const
00258 {
00259   return cam_info_.nMaxWidth;
00260 }
00261 int Camera::getHeightMax() const
00262 {
00263   return cam_info_.nMaxHeight;
00264 }
00265 int Camera::getWidth() const
00266 {
00267   return cam_info_.nMaxWidth / zoom_;
00268 }
00269 int Camera::getHeight() const
00270 {
00271   return cam_info_.nMaxHeight / zoom_;
00272 }
00273 uEyeColor Camera::getColorMode() const
00274 {
00275   return color_mode_;
00276 }
00277 bool Camera::getAutoExposure() const
00278 {
00279   return auto_exposure_;
00280 }
00281 double Camera::getExposure() const
00282 {
00283   double time_ms;
00284   checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_GET_EXPOSURE, &time_ms, sizeof(double)));
00285   return time_ms;
00286 }
00287 bool Camera::getHardwareGamma() const
00288 {
00289   return hardware_gamma_;
00290 }
00291 int Camera::getPixelClock() const
00292 {
00293   return pixel_clock_;
00294 }
00295 bool Camera::getGainBoost() const
00296 {
00297   return gain_boost_;
00298 }
00299 bool Camera::getAutoGain() const
00300 {
00301   return auto_gain_;
00302 }
00303 unsigned int Camera::getHardwareGain()
00304 {
00305   hardware_gain_ = is_SetHWGainFactor(cam_, IS_GET_MASTER_GAIN_FACTOR, 0);
00306   return hardware_gain_;
00307 }
00308 TriggerMode Camera::getTriggerMode() const
00309 {
00310   return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_EXTERNALTRIGGER);
00311 }
00312 TriggerMode Camera::getSupportedTriggers() const
00313 {
00314   return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_SUPPORTED_TRIGGER_MODE);
00315 }
00316 
00317 void Camera::setColorMode(uEyeColor mode)
00318 {
00319   bool restart = streaming_ && (stream_callback_ != NULL);
00320   stopVideoCapture();
00321   if (is_SetColorMode(cam_, mode) != IS_SUCCESS) {
00322     mode = MONO8;
00323     is_SetColorMode(cam_, mode);
00324   }
00325   color_mode_ = mode;
00326   if (restart) {
00327     startVideoCapture(stream_callback_);
00328   }
00329 }
00330 void Camera::setAutoExposure(bool *enable)
00331 {
00332   double param1 = *enable ? 1.0 : 0.0;
00333   double param2 = 0;
00334   if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2)) {
00335     param1 = 0;
00336     is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, &param1, &param2);
00337     *enable = false;
00338   }
00339   auto_exposure_ = *enable;
00340 }
00341 void Camera::setExposure(double *time_ms)
00342 {
00343   bool b = false;
00344   setAutoExposure(&b);
00345   checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_SET_EXPOSURE, time_ms, sizeof(double)));
00346   flashUpdateGlobalParams();
00347   exposure_time_ = *time_ms;
00348 }
00349 void Camera::setHardwareGamma(bool *enable)
00350 {
00351   if (*enable) {
00352     if (IS_SUCCESS != is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_ON)) {
00353       is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
00354       *enable = false;
00355     }
00356   } else {
00357     is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
00358   }
00359   hardware_gamma_ = *enable;
00360 }
00361 void Camera::setZoom(int *zoom)
00362 {
00363   if (zoom_ != *zoom) {
00364     // Reset zoom
00365     is_SetSubSampling(cam_, 0);
00366     is_SetBinning(cam_, 0);
00367 
00368     // Try Subsampling then Binning
00369     if (IS_SUCCESS != is_SetSubSampling(cam_, getSubsampleParam(zoom))) {
00370       is_SetSubSampling(cam_, 0);
00371       if (IS_SUCCESS != is_SetBinning(cam_, getBinningParam(zoom))) {
00372         is_SetBinning(cam_, 0);
00373         *zoom = 1;
00374       }
00375     }
00376 
00377     // Zoom affects the frame-rate and needs a restart to change the buffer sizes
00378     is_HotPixel(cam_, IS_HOTPIXEL_ENABLE_CAMERA_CORRECTION, NULL, 0);
00379     setFrameRate(&frame_rate_);
00380     restartVideoCapture();
00381   }
00382   zoom_ = *zoom;
00383 }
00384 void Camera::setPixelClock(int *MHz)
00385 {
00386   int ranges[3];
00387   memset(ranges, 0x00, sizeof(ranges));
00388 
00389   // Sanitize to increment, minimum, and maximum
00390   checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_GET_RANGE, ranges, sizeof(ranges)));
00391   if (ranges[2] > 1) {
00392     if ((*MHz - ranges[0]) % ranges[2] != 0) {
00393       *MHz -= (*MHz - ranges[0]) % ranges[2];
00394     }
00395   }
00396   if (*MHz < ranges[0]) {
00397     *MHz = ranges[0];
00398   }
00399   if (*MHz > ranges[1]) {
00400     *MHz = ranges[1];
00401   }
00402 
00403   checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_SET, MHz, sizeof(int)));
00404   setFrameRate(&frame_rate_);
00405 
00406   pixel_clock_ = *MHz;
00407 }
00408 void Camera::setFrameRate(double *rate)
00409 {
00410   checkError(is_SetFrameRate(cam_, *rate, rate));
00411   flashUpdateGlobalParams();
00412   frame_rate_ = *rate;
00413 }
00414 void Camera::setGainBoost(bool *enable)
00415 {
00416   if (is_SetGainBoost(cam_, IS_GET_SUPPORTED_GAINBOOST) == IS_SET_GAINBOOST_ON) {
00417     if (*enable)
00418       is_SetGainBoost(cam_, IS_SET_GAINBOOST_ON);
00419     else
00420       is_SetGainBoost(cam_, IS_SET_GAINBOOST_OFF);
00421     gain_boost_ = is_SetGainBoost(cam_, IS_GET_GAINBOOST) == IS_SET_GAINBOOST_ON;
00422   } else {
00423     gain_boost_ = false;
00424   }
00425   *enable = gain_boost_;
00426 }
00427 void Camera::setAutoGain(bool *enable)
00428 {
00429   double param1 = *enable ? 1.0 : 0.0;
00430   double param2 = 0;
00431   if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2)) {
00432     param1 = 0;
00433     is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, &param1, &param2);
00434     *enable = false;
00435   }
00436   auto_gain_ = *enable;
00437 }
00438 void Camera::setHardwareGain(int *gain)
00439 {
00440   bool b = false;
00441   setAutoGain(&b);
00442   if (*gain < 0)
00443     *gain = 0;
00444   if (*gain > 400)
00445     *gain = 400;
00446   hardware_gain_ = is_SetHWGainFactor(cam_, IS_SET_MASTER_GAIN_FACTOR, *gain);
00447   *gain = hardware_gain_;
00448 }
00449 bool Camera::setTriggerMode(TriggerMode mode)
00450 {
00451   if ((mode == 0) || (mode & getSupportedTriggers())) {
00452     if (is_SetExternalTrigger(cam_, mode) == IS_SUCCESS) {
00453       return true;
00454     }
00455   }
00456   return false;
00457 }
00458 void Camera::setFlashWithGlobalParams(FlashMode mode)
00459 {
00460   UINT m = mode;
00461   switch (mode) {
00462     case FLASH_FREERUN_ACTIVE_LO:
00463     case FLASH_FREERUN_ACTIVE_HI:
00464     case FLASH_TRIGGER_ACTIVE_LO:
00465     case FLASH_TRIGGER_ACTIVE_HI:
00466       flash_global_params_ = true;
00467       break;
00468 
00469     case FLASH_CONSTANT_HIGH:
00470     case FLASH_CONSTANT_LOW:
00471       flash_global_params_ = false;
00472       break;
00473 
00474     case FLASH_OFF:
00475     default:
00476       flash_global_params_ = false;
00477       m = FLASH_OFF;
00478       break;
00479   }
00480   checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&m, sizeof(m)));
00481   flashUpdateGlobalParams();
00482 }
00483 void Camera::setFlash(FlashMode mode, int delay_usec, unsigned int duration_usec)
00484 {
00485   int num_mode = int(mode);
00486 
00487   checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&num_mode, sizeof(num_mode)));
00488 
00489   if (mode != FLASH_OFF) {
00490     IO_FLASH_PARAMS params;
00491     memset(&params, 0, sizeof(params));
00492 
00493     params.s32Delay = delay_usec;
00494     params.u32Duration = duration_usec;
00495 
00496     checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_PARAMS, &params, sizeof(params)));
00497   }
00498 
00499   flash_global_params_ = false;
00500 }
00501 void Camera::setFlash(FlashMode mode)
00502 {
00503   // If flash delay = 0 and flash duration = 0, the flash signal is
00504   // automatically synchronized to the exposure time.
00505   setFlash(mode, 0, 0);
00506 }
00507 void Camera::flashUpdateGlobalParams()
00508 {
00509   if (flash_global_params_) {
00510     IO_FLASH_PARAMS params;
00511     checkError(is_IO(cam_, IS_IO_CMD_FLASH_GET_GLOBAL_PARAMS, (void*)&params, sizeof(params)));
00512     checkError(is_IO(cam_, IS_IO_CMD_FLASH_APPLY_GLOBAL_PARAMS, NULL, 0));
00513   }
00514 }
00515 void Camera::setTriggerDelay(int delay_usec)
00516 {
00517   checkError(is_SetTriggerDelay(cam_, delay_usec));
00518 }
00519 
00520 bool Camera::forceTrigger()
00521 {
00522   if (streaming_)
00523     return is_ForceTrigger(cam_) == IS_SUCCESS;
00524   return false;
00525 }
00526 
00527 int Camera::getSubsampleParam(int *scale)
00528 {
00529   int param;
00530   if (*scale == 3) {
00531     *scale = 2;
00532   }
00533   switch (*scale) {
00534     case 2:
00535       param = IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL;
00536       break;
00537     case 4:
00538       param = IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL;
00539       break;
00540     default:
00541       *scale = 1;
00542       param = IS_SUBSAMPLING_DISABLE;
00543       break;
00544   }
00545   return param;
00546 }
00547 int Camera::getBinningParam(int *scale)
00548 {
00549   int param;
00550   if (*scale == 3) {
00551     *scale = 2;
00552   }
00553   switch (*scale) {
00554     case 2:
00555       param = IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL;
00556       break;
00557     case 4:
00558       param = IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL;
00559       break;
00560     default:
00561       *scale = 1;
00562       param = IS_BINNING_DISABLE;
00563       break;
00564   }
00565   return param;
00566 }
00567 
00568 void Camera::closeCamera()
00569 {
00570   if (cam_ > 0) {
00571     // Release camera and all associated memory
00572     checkError(IS_SUCCESS != is_ExitCamera(cam_));
00573     initPrivateVariables();
00574   }
00575 }
00576 
00577 Camera::~Camera()
00578 {
00579   closeCamera();
00580 }
00581 
00582 void Camera::initMemoryPool(int size)
00583 {
00584   int bits = 32;
00585   switch (color_mode_) {
00586     case MONO8:
00587       bits = 8;
00588       break;
00589     case MONO16:
00590     case BGR5:
00591     case BGR565:
00592     case YUV:
00593     case YCbCr:
00594       bits = 16;
00595       break;
00596     case BGR8:
00597     case RGB8:
00598       bits = 24;
00599       break;
00600     case BGRA8:
00601     case BGRY8:
00602     case RGBA8:
00603     case RGBY8:
00604       bits = 32;
00605       break;
00606   }
00607 
00608   int width = getWidth();
00609   int height = getHeight();
00610   if (size < 2) {
00611     size = 2;
00612   }
00613   img_mem_.resize(size);
00614   img_mem_id_.resize(size);
00615   for (int i = 0; i < size; i++) {
00616     if (IS_SUCCESS != is_AllocImageMem(cam_, width, height, bits, &img_mem_[i], &img_mem_id_[i])) {
00617       throw uEyeException(-1, "Failed to initialize memory.");
00618     }
00619     //add memory to memory pool
00620     if (IS_SUCCESS != is_SetImageMem(cam_, img_mem_[i], img_mem_id_[i])) {
00621       throw uEyeException(-1, "Failed to initialize memory.");
00622     }
00623   }
00624 }
00625 void Camera::destroyMemoryPool()
00626 {
00627   for (int i = 0; i < img_mem_.size(); i++) {
00628     checkError(is_FreeImageMem(cam_, img_mem_[i], img_mem_id_[i]));
00629   }
00630   img_mem_.clear();
00631   img_mem_id_.clear();
00632 }
00633 
00634 void Camera::captureThread(CamCaptureCB callback)
00635 {
00636   streaming_ = true;
00637   char * img_mem;
00638   stop_capture_ = false;
00639 
00640   initMemoryPool(4);
00641 
00642   // Setup video event
00643   checkError(is_EnableEvent(cam_, IS_SET_EVENT_FRAME));
00644 
00645   // There is a weird condition with the uEye SDK 4.30 where
00646   // this never returns when using IS_WAIT.
00647   // We are using IS_DONT_WAIT and retry every 0.1s for 2s instead
00648   bool capture = false;
00649   for (int i = 0; i < 20; ++i) {
00650     if (is_CaptureVideo(cam_, IS_DONT_WAIT) == IS_SUCCESS) {
00651       capture = true;
00652       break;
00653     }
00654     usleep(100000); // 100ms
00655   }
00656   if (!capture) {
00657     throw uEyeException(-1, "Capture could not be started.");
00658   }
00659 
00660   IplImage *p_img = NULL;
00661   switch (color_mode_) {
00662     case MONO8:
00663       p_img = cvCreateImageHeader(cvSize(getWidth(), getHeight()), IPL_DEPTH_8U, 1);
00664       break;
00665     case MONO16:
00666     case BGR5:
00667     case BGR565:
00668       p_img = cvCreateImageHeader(cvSize(getWidth(), getHeight()), IPL_DEPTH_16U, 1);
00669       break;
00670     case YUV:
00671     case YCbCr:
00672       p_img = cvCreateImageHeader(cvSize(getWidth(), getHeight()), IPL_DEPTH_8U, 2);
00673       break;
00674     case BGR8:
00675     case RGB8:
00676       p_img = cvCreateImageHeader(cvSize(getWidth(), getHeight()), IPL_DEPTH_8U, 3);
00677       break;
00678     case BGRA8:
00679     case BGRY8:
00680     case RGBA8:
00681     case RGBY8:
00682       p_img = cvCreateImageHeader(cvSize(getWidth(), getHeight()), IPL_DEPTH_8U, 4);
00683       break;
00684     default:
00685       throw uEyeException(-1, "Unsupported color mode when initializing image header.");
00686       return;
00687   }
00688 
00689   while (!stop_capture_) {
00690     // Wait for image. Timeout after 2*FramePeriod = (2000ms/FrameRate)
00691     if (is_WaitEvent(cam_, IS_SET_EVENT_FRAME, (int)(2000 / frame_rate_)) == IS_SUCCESS) {
00692       if (is_GetImageMem(cam_, (void**)&img_mem) == IS_SUCCESS) {
00693         p_img->imageData = img_mem;
00694         callback(p_img);
00695       }
00696     }
00697   }
00698 
00699   // Stop video event
00700   checkError(is_DisableEvent(cam_, IS_SET_EVENT_FRAME));
00701   checkError(is_StopLiveVideo(cam_, IS_WAIT));
00702 
00703   destroyMemoryPool();
00704   streaming_ = false;
00705 }
00706 
00707 void Camera::startVideoCapture(CamCaptureCB callback)
00708 {
00709   stream_callback_ = callback;
00710   thread_ = boost::thread(&Camera::captureThread, this, callback);
00711 }
00712 void Camera::stopVideoCapture()
00713 {
00714   stop_capture_ = true;
00715   if (thread_.joinable()) {
00716     forceTrigger();
00717     thread_.join();
00718   }
00719 }
00720 void Camera::restartVideoCapture()
00721 {
00722   if (streaming_) {
00723     if (stream_callback_ != NULL) {
00724       stopVideoCapture();
00725       startVideoCapture(stream_callback_);
00726     }
00727   }
00728 }
00729 
00730 } //namespace ueye


ueye
Author(s): Kevin Hallenbeck
autogenerated on Mon Oct 6 2014 08:20:20