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 #include <ueye/Camera.h>
00036
00037
00038 #if defined(__i386) || defined(__i386__) || defined(_M_IX86)
00039 #define EXPECTED_VERSION_MAJOR 4
00040 #define EXPECTED_VERSION_MINOR 60
00041 #define EXPECTED_VERSION_BUILD 5
00042 #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00043 #warning Expected ueye driver version 4.60.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 60
00048 #define EXPECTED_VERSION_BUILD 5
00049 #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00050 #warning Expected ueye driver version 4.60.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 60
00055 #define EXPECTED_VERSION_BUILD 0
00056 #if UEYE_VERSION_CODE != UEYE_VERSION(EXPECTED_VERSION_MAJOR, EXPECTED_VERSION_MINOR, 0)
00057 #warning Expected ueye driver version 4.60.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::initPrivateVariables()
00081 {
00082 streaming_ = false;
00083 stop_capture_ = false;
00084 color_mode_ = MONO8;
00085 auto_exposure_ = false;
00086 exposure_time_ = 99.0;
00087 hardware_gamma_ = true;
00088 gain_boost_ = false;
00089 zoom_ = 1;
00090 pixel_clock_ = 20;
00091 auto_gain_ = false;
00092 hardware_gain_ = 100;
00093 frame_rate_ = 5.0;
00094 flash_global_params_ = false;
00095 serial_number_ = 0;
00096 cam_ = 0;
00097 memset(&cam_info_, 0x00, sizeof(cam_info_));
00098 stream_callback_ = NULL;
00099 }
00100
00101 Camera::Camera()
00102 {
00103 initPrivateVariables();
00104 }
00105
00106 #define STR_HELPER(x) #x
00107 #define STR(x) STR_HELPER(x)
00108 bool Camera::checkVersion(int &major, int &minor, int &build, const char *&expected)
00109 {
00110 expected = STR(EXPECTED_VERSION_MAJOR) "." STR(EXPECTED_VERSION_MINOR) "." STR(EXPECTED_VERSION_BUILD);
00111 build = is_GetDLLVersion();
00112 major = (build >> 24) & 0x000000FF;
00113 minor = (build >> 16) & 0x000000FF;
00114 build &= 0x0000FFFF;
00115 if ((major == EXPECTED_VERSION_MAJOR) && (minor == EXPECTED_VERSION_MINOR) && (build == EXPECTED_VERSION_BUILD)) {
00116 return true;
00117 }
00118 return false;
00119 }
00120 #undef STR_HELPER
00121 #undef STR
00122
00123 int Camera::getNumberOfCameras() const
00124 {
00125 int num = 0;
00126 checkError(is_GetNumberOfCameras(&num));
00127 return num;
00128 }
00129
00130 unsigned int Camera::getSerialNumberList(std::vector<unsigned int>& serial, std::vector<unsigned int>& dev_id)
00131 {
00132 int num = getNumberOfCameras();
00133 if (num > 0) {
00134 UEYE_CAMERA_LIST *list = (UEYE_CAMERA_LIST *)malloc(sizeof(DWORD) + num * sizeof(UEYE_CAMERA_INFO));
00135 list->dwCount = num;
00136 if (is_GetCameraList(list) == IS_SUCCESS) {
00137 num = list->dwCount;
00138 serial.resize(num);
00139 dev_id.resize(num);
00140 for (int i = 0; i < num; i++) {
00141 serial[i] = atoll(list->uci[i].SerNo);
00142 dev_id[i] = list->uci[i].dwDeviceID;
00143 }
00144 } else {
00145 num = 0;
00146 }
00147 free(list);
00148 return num;
00149 }
00150 return 0;
00151 }
00152
00153 bool Camera::openCameraCamId(unsigned int id)
00154 {
00155 if (getNumberOfCameras() < 1) {
00156 return false;
00157 }
00158
00159 cam_ = id;
00160 checkError(is_InitCamera(&cam_, 0));
00161
00162 checkError(is_GetSensorInfo(cam_, &cam_info_));
00163 CAMINFO info;
00164 checkError(is_GetCameraInfo(cam_, &info));
00165 serial_number_ = atoll(info.SerNo);
00166
00167 setColorMode(color_mode_);
00168 setAutoExposure(&auto_exposure_);
00169 if (!auto_exposure_) {
00170 setExposure(&exposure_time_);
00171 }
00172 setHardwareGamma(&hardware_gamma_);
00173 setGainBoost(&gain_boost_);
00174 setAutoGain(&auto_gain_);
00175 if (!auto_gain_) {
00176 setHardwareGain(&hardware_gain_);
00177 }
00178 setZoom(&zoom_);
00179 setPixelClock(&pixel_clock_);
00180 setFrameRate(&frame_rate_);
00181 return true;
00182 }
00183 bool Camera::openCameraDevId(unsigned int id)
00184 {
00185 return openCameraCamId(id | IS_USE_DEVICE_ID);
00186 }
00187 bool Camera::openCameraSerNo(unsigned int serial_number)
00188 {
00189 std::vector<unsigned int> serial;
00190 std::vector<unsigned int> dev_id;
00191 unsigned int num = getSerialNumberList(serial, dev_id);
00192 for (unsigned int i = 0; i < num; i++) {
00193 if (serial[i] == serial_number) {
00194 return openCameraDevId(dev_id[i]);
00195 }
00196 }
00197 return false;
00198 }
00199
00200 const char* Camera::colorModeToString(uEyeColor mode)
00201 {
00202 switch (mode) {
00203 case MONO8:
00204 return "mono8";
00205 case MONO16:
00206 return "mono16";
00207 case BGR5:
00208 return "bgr5";
00209 case BGR565:
00210 return "bgr565";
00211 case YUV:
00212 return "yuv422";
00213 case YCbCr:
00214 return "ycbcr422";
00215 case BGR8:
00216 return "bgr8";
00217 case RGB8:
00218 return "rgb8";
00219 case BGRA8:
00220 case BGRY8:
00221 return "bgra8";
00222 case RGBA8:
00223 case RGBY8:
00224 return "rgba8";
00225 }
00226 return "";
00227 }
00228
00229 double Camera::getExposure()
00230 {
00231 double time_ms;
00232 checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_GET_EXPOSURE, &time_ms, sizeof(double)));
00233 return time_ms;
00234 }
00235 unsigned int Camera::getHardwareGain()
00236 {
00237 hardware_gain_ = is_SetHWGainFactor(cam_, IS_GET_MASTER_GAIN_FACTOR, 0);
00238 return hardware_gain_;
00239 }
00240 TriggerMode Camera::getTriggerMode()
00241 {
00242 return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_EXTERNALTRIGGER);
00243 }
00244 TriggerMode Camera::getSupportedTriggers()
00245 {
00246 return (TriggerMode)is_SetExternalTrigger(cam_, IS_GET_SUPPORTED_TRIGGER_MODE);
00247 }
00248
00249 void Camera::setColorMode(uEyeColor mode)
00250 {
00251 bool restart = streaming_ && (stream_callback_ != NULL);
00252 stopVideoCapture();
00253 if (is_SetColorMode(cam_, mode) != IS_SUCCESS) {
00254 mode = MONO8;
00255 is_SetColorMode(cam_, mode);
00256 }
00257 color_mode_ = mode;
00258 if (restart) {
00259 startVideoCapture(stream_callback_);
00260 }
00261 }
00262 void Camera::setAutoExposure(bool *enable)
00263 {
00264 double param1 = *enable ? 1.0 : 0.0;
00265 double param2 = 0;
00266 if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, ¶m1, ¶m2)) {
00267 param1 = 0;
00268 is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_SHUTTER, ¶m1, ¶m2);
00269 *enable = false;
00270 }
00271 auto_exposure_ = *enable;
00272 }
00273 void Camera::setExposure(double *time_ms)
00274 {
00275 bool b = false;
00276 setAutoExposure(&b);
00277 checkError(is_Exposure(cam_, IS_EXPOSURE_CMD_SET_EXPOSURE, time_ms, sizeof(double)));
00278 flashUpdateGlobalParams();
00279 exposure_time_ = *time_ms;
00280 }
00281 void Camera::setHardwareGamma(bool *enable)
00282 {
00283 if (*enable) {
00284 if (IS_SUCCESS != is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_ON)) {
00285 is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
00286 *enable = false;
00287 }
00288 } else {
00289 is_SetHardwareGamma(cam_, IS_SET_HW_GAMMA_OFF);
00290 }
00291 hardware_gamma_ = *enable;
00292 }
00293 void Camera::setZoom(int *zoom)
00294 {
00295 if (zoom_ != *zoom) {
00296
00297 is_SetSubSampling(cam_, 0);
00298 is_SetBinning(cam_, 0);
00299
00300
00301 if (IS_SUCCESS != is_SetSubSampling(cam_, getSubsampleParam(zoom))) {
00302 is_SetSubSampling(cam_, 0);
00303 if (IS_SUCCESS != is_SetBinning(cam_, getBinningParam(zoom))) {
00304 is_SetBinning(cam_, 0);
00305 *zoom = 1;
00306 }
00307 }
00308
00309
00310 is_HotPixel(cam_, IS_HOTPIXEL_ENABLE_CAMERA_CORRECTION, NULL, 0);
00311 setFrameRate(&frame_rate_);
00312 restartVideoCapture();
00313 }
00314 zoom_ = *zoom;
00315 }
00316 void Camera::setPixelClock(int *MHz)
00317 {
00318 int pixelClockList[150];
00319 int numberOfSupportedPixelClocks = 0;
00320 checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_GET_NUMBER, &numberOfSupportedPixelClocks, sizeof(numberOfSupportedPixelClocks)));
00321 if(numberOfSupportedPixelClocks > 0) {
00322 memset(pixelClockList, 0x00, sizeof(pixelClockList));
00323 checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_GET_LIST, pixelClockList, numberOfSupportedPixelClocks * sizeof(int)));
00324 }
00325 int minPixelClock = pixelClockList[0];
00326 int maxPixelClock = pixelClockList[numberOfSupportedPixelClocks-1];
00327
00328
00329 for(int i = 0; i < numberOfSupportedPixelClocks; i++) {
00330 if(*MHz <= pixelClockList[i]) {
00331 *MHz = pixelClockList[i];
00332 break;
00333 }
00334 }
00335
00336 if (*MHz < minPixelClock) {
00337 *MHz = minPixelClock;
00338 }
00339 if (*MHz > maxPixelClock) {
00340 *MHz = maxPixelClock;
00341 }
00342
00343 checkError(is_PixelClock(cam_, IS_PIXELCLOCK_CMD_SET, MHz, sizeof(int)));
00344 setFrameRate(&frame_rate_);
00345
00346 pixel_clock_ = *MHz;
00347 }
00348 void Camera::setFrameRate(double *rate)
00349 {
00350 checkError(is_SetFrameRate(cam_, *rate, rate));
00351 flashUpdateGlobalParams();
00352 frame_rate_ = *rate;
00353 }
00354 void Camera::setGainBoost(bool *enable)
00355 {
00356 if (is_SetGainBoost(cam_, IS_GET_SUPPORTED_GAINBOOST) == IS_SET_GAINBOOST_ON) {
00357 if (*enable)
00358 is_SetGainBoost(cam_, IS_SET_GAINBOOST_ON);
00359 else
00360 is_SetGainBoost(cam_, IS_SET_GAINBOOST_OFF);
00361 gain_boost_ = is_SetGainBoost(cam_, IS_GET_GAINBOOST) == IS_SET_GAINBOOST_ON;
00362 } else {
00363 gain_boost_ = false;
00364 }
00365 *enable = gain_boost_;
00366 }
00367 void Camera::setAutoGain(bool *enable)
00368 {
00369 double param1 = *enable ? 1.0 : 0.0;
00370 double param2 = 0;
00371 if (IS_SUCCESS != is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, ¶m1, ¶m2)) {
00372 param1 = 0;
00373 is_SetAutoParameter(cam_, IS_SET_ENABLE_AUTO_GAIN, ¶m1, ¶m2);
00374 *enable = false;
00375 }
00376 auto_gain_ = *enable;
00377 }
00378 void Camera::setHardwareGain(int *gain)
00379 {
00380 bool b = false;
00381 setAutoGain(&b);
00382 if (*gain < 0)
00383 *gain = 0;
00384 if (*gain > 400)
00385 *gain = 400;
00386 hardware_gain_ = is_SetHWGainFactor(cam_, IS_SET_MASTER_GAIN_FACTOR, *gain);
00387 *gain = hardware_gain_;
00388 }
00389 bool Camera::setTriggerMode(TriggerMode mode)
00390 {
00391 if ((mode == 0) || (mode & getSupportedTriggers())) {
00392 if (is_SetExternalTrigger(cam_, mode) == IS_SUCCESS) {
00393 return true;
00394 }
00395 }
00396 return false;
00397 }
00398 void Camera::setFlashWithGlobalParams(FlashMode mode)
00399 {
00400 UINT m = mode;
00401 switch (mode) {
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 flash_global_params_ = true;
00407 break;
00408
00409 case FLASH_CONSTANT_HIGH:
00410 case FLASH_CONSTANT_LOW:
00411 flash_global_params_ = false;
00412 break;
00413
00414 case FLASH_OFF:
00415 default:
00416 flash_global_params_ = false;
00417 m = FLASH_OFF;
00418 break;
00419 }
00420 checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&m, sizeof(m)));
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 checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_MODE, (void*)&num_mode, sizeof(num_mode)));
00428
00429 if (mode != FLASH_OFF) {
00430 IO_FLASH_PARAMS params;
00431 memset(¶ms, 0, sizeof(params));
00432
00433 params.s32Delay = delay_usec;
00434 params.u32Duration = duration_usec;
00435
00436 checkError(is_IO(cam_, IS_IO_CMD_FLASH_SET_PARAMS, ¶ms, sizeof(params)));
00437 }
00438
00439 flash_global_params_ = false;
00440 }
00441 void Camera::setFlash(FlashMode mode)
00442 {
00443
00444
00445 setFlash(mode, 0, 0);
00446 }
00447 void Camera::flashUpdateGlobalParams()
00448 {
00449 if (flash_global_params_) {
00450 IO_FLASH_PARAMS params;
00451 checkError(is_IO(cam_, IS_IO_CMD_FLASH_GET_GLOBAL_PARAMS, (void*)¶ms, sizeof(params)));
00452 checkError(is_IO(cam_, IS_IO_CMD_FLASH_APPLY_GLOBAL_PARAMS, NULL, 0));
00453 }
00454 }
00455 void Camera::setTriggerDelay(int delay_usec)
00456 {
00457 checkError(is_SetTriggerDelay(cam_, delay_usec));
00458 }
00459
00460 bool Camera::forceTrigger()
00461 {
00462 if (streaming_)
00463 return is_ForceTrigger(cam_) == IS_SUCCESS;
00464 return false;
00465 }
00466
00467 int Camera::getSubsampleParam(int *scale)
00468 {
00469 int param;
00470 switch (*scale) {
00471 case 2:
00472 param = IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL;
00473 break;
00474 case 3:
00475 param = IS_SUBSAMPLING_3X_VERTICAL | IS_SUBSAMPLING_3X_HORIZONTAL;
00476 break;
00477 case 4:
00478 param = IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL;
00479 break;
00480 case 5:
00481 param = IS_SUBSAMPLING_5X_VERTICAL | IS_SUBSAMPLING_5X_HORIZONTAL;
00482 break;
00483 case 6:
00484 param = IS_SUBSAMPLING_6X_VERTICAL | IS_SUBSAMPLING_6X_HORIZONTAL;
00485 break;
00486 case 7:
00487 case 8:
00488 *scale = 8;
00489 param = IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL;
00490 break;
00491 case 9:
00492 case 10:
00493 case 11:
00494 case 12:
00495 case 13:
00496 case 14:
00497 case 15:
00498 case 16:
00499 *scale = 16;
00500 param = IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL;
00501 break;
00502 default:
00503 *scale = 1;
00504 param = IS_SUBSAMPLING_DISABLE;
00505 break;
00506 }
00507 return param;
00508 }
00509 int Camera::getBinningParam(int *scale)
00510 {
00511 int param;
00512 switch (*scale) {
00513 case 2:
00514 param = IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL;
00515 break;
00516 case 3:
00517 param = IS_BINNING_3X_VERTICAL | IS_BINNING_3X_HORIZONTAL;
00518 break;
00519 case 4:
00520 param = IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL;
00521 break;
00522 case 5:
00523 param = IS_BINNING_5X_VERTICAL | IS_BINNING_5X_HORIZONTAL;
00524 break;
00525 case 6:
00526 param = IS_BINNING_6X_VERTICAL | IS_BINNING_6X_HORIZONTAL;
00527 break;
00528 case 7:
00529 case 8:
00530 *scale = 8;
00531 param = IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL;
00532 break;
00533 case 9:
00534 case 10:
00535 case 11:
00536 case 12:
00537 case 13:
00538 case 14:
00539 case 15:
00540 case 16:
00541 *scale = 16;
00542 param = IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL;
00543 break;
00544 default:
00545 *scale = 1;
00546 param = IS_BINNING_DISABLE;
00547 break;
00548 }
00549 return param;
00550 }
00551
00552 void Camera::closeCamera()
00553 {
00554 if (cam_ > 0) {
00555
00556 checkError(IS_SUCCESS != is_ExitCamera(cam_));
00557 initPrivateVariables();
00558 }
00559 }
00560
00561 Camera::~Camera()
00562 {
00563 closeCamera();
00564 }
00565
00566 void Camera::initMemoryPool(int size)
00567 {
00568 int bits = 32;
00569 switch (color_mode_) {
00570 case MONO8:
00571 bits = 8;
00572 break;
00573 case MONO16:
00574 case BGR5:
00575 case BGR565:
00576 case YUV:
00577 case YCbCr:
00578 bits = 16;
00579 break;
00580 case BGR8:
00581 case RGB8:
00582 bits = 24;
00583 break;
00584 case BGRA8:
00585 case BGRY8:
00586 case RGBA8:
00587 case RGBY8:
00588 bits = 32;
00589 break;
00590 }
00591
00592 int width = getWidth();
00593 int height = getHeight();
00594 if (size < 2) {
00595 size = 2;
00596 }
00597 img_mem_.resize(size);
00598 img_mem_id_.resize(size);
00599 for (int i = 0; i < size; i++) {
00600 if (IS_SUCCESS != is_AllocImageMem(cam_, width, height, bits, &img_mem_[i], &img_mem_id_[i])) {
00601 throw uEyeException(-1, "Failed to initialize memory.");
00602 }
00603
00604 if (IS_SUCCESS != is_SetImageMem(cam_, img_mem_[i], img_mem_id_[i])) {
00605 throw uEyeException(-1, "Failed to initialize memory.");
00606 }
00607 }
00608 }
00609 void Camera::destroyMemoryPool()
00610 {
00611 for (int i = 0; i < img_mem_.size(); i++) {
00612 checkError(is_FreeImageMem(cam_, img_mem_[i], img_mem_id_[i]));
00613 }
00614 img_mem_.clear();
00615 img_mem_id_.clear();
00616 }
00617
00618 void Camera::captureThread(CamCaptureCB callback)
00619 {
00620 streaming_ = true;
00621 stop_capture_ = false;
00622
00623 initMemoryPool(4);
00624
00625
00626 checkError(is_EnableEvent(cam_, IS_SET_EVENT_FRAME));
00627
00628
00629
00630
00631 bool capture = false;
00632 for (int i = 0; i < 20; ++i) {
00633 if (is_CaptureVideo(cam_, IS_DONT_WAIT) == IS_SUCCESS) {
00634 capture = true;
00635 break;
00636 }
00637 usleep(100000);
00638 }
00639 if (!capture) {
00640 throw uEyeException(-1, "Capture could not be started.");
00641 }
00642
00643 size_t depth = 0;
00644 switch (color_mode_) {
00645 case MONO8:
00646 depth = 1;
00647 break;
00648 case MONO16:
00649 case BGR5:
00650 case BGR565:
00651 depth = 1;
00652 break;
00653 case YUV:
00654 case YCbCr:
00655 depth = 2;
00656 break;
00657 case BGR8:
00658 case RGB8:
00659 depth = 3;
00660 break;
00661 case BGRA8:
00662 case BGRY8:
00663 case RGBA8:
00664 case RGBY8:
00665 depth = 4;
00666 break;
00667 default:
00668 throw uEyeException(-1, "Unsupported color mode when initializing image header.");
00669 return;
00670 }
00671 size_t size = (size_t)getWidth() * (size_t)getHeight() * depth;
00672
00673 char *img_mem;
00674 while (!stop_capture_) {
00675
00676 if (is_WaitEvent(cam_, IS_SET_EVENT_FRAME, (int)(2000 / frame_rate_)) == IS_SUCCESS) {
00677 if (is_GetImageMem(cam_, (void**)&img_mem) == IS_SUCCESS) {
00678 callback(img_mem, size);
00679 }
00680 }
00681 }
00682
00683
00684 checkError(is_DisableEvent(cam_, IS_SET_EVENT_FRAME));
00685 checkError(is_StopLiveVideo(cam_, IS_WAIT));
00686
00687 destroyMemoryPool();
00688 streaming_ = false;
00689 }
00690
00691 void Camera::startVideoCapture(CamCaptureCB callback)
00692 {
00693 stream_callback_ = callback;
00694 thread_ = boost::thread(&Camera::captureThread, this, callback);
00695 }
00696 void Camera::stopVideoCapture()
00697 {
00698 stop_capture_ = true;
00699 if (thread_.joinable()) {
00700 forceTrigger();
00701 thread_.join();
00702 }
00703 }
00704 void Camera::restartVideoCapture()
00705 {
00706 if (streaming_) {
00707 if (stream_callback_ != NULL) {
00708 stopVideoCapture();
00709 startVideoCapture(stream_callback_);
00710 }
00711 }
00712 }
00713
00714 }