ueye_cam_driver.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * DO NOT MODIFY - AUTO-GENERATED
00003 *
00004 *
00005 * DISCLAMER:
00006 *
00007 * This project was created within an academic research setting, and thus should
00008 * be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
00009 * code, so please adjust expectations accordingly. With that said, we are
00010 * intrinsically motivated to ensure its correctness (and often its performance).
00011 * Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
00012 * to file bugs, suggestions, pull requests; we will do our best to address them
00013 * in a timely manner.
00014 *
00015 *
00016 * SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
00017 *
00018 * Copyright (c) 2013, Anqi Xu
00019 * All rights reserved.
00020 *
00021 * Redistribution and use in source and binary forms, with or without
00022 * modification, are permitted provided that the following conditions
00023 * are met:
00024 *
00025 *  * Redistributions of source code must retain the above copyright
00026 *    notice, this list of conditions and the following disclaimer.
00027 *  * Redistributions in binary form must reproduce the above
00028 *    copyright notice, this list of conditions and the following
00029 *    disclaimer in the documentation and/or other materials provided
00030 *    with the distribution.
00031 *  * Neither the name of the School of Computer Science, McGill University,
00032 *    nor the names of its contributors may be used to endorse or promote
00033 *    products derived from this software without specific prior written
00034 *    permission.
00035 *
00036 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00037 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00038 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00039 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
00040 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00041 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00042 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00043 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00044 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00045 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00046 *******************************************************************************/
00047 
00048 #include "ueye_cam/ueye_cam_driver.hpp"
00049 
00050 
00051 using namespace std;
00052 
00053 
00054 namespace ueye_cam {
00055 
00056 
00057 UEyeCamDriver::UEyeCamDriver(int cam_ID, string cam_name) :
00058     cam_handle_((HIDS) 0),
00059     cam_buffer_(NULL),
00060     cam_buffer_id_(0),
00061     cam_buffer_pitch_(0),
00062     cam_buffer_size_(0),
00063     cam_name_(cam_name),
00064     cam_id_(cam_ID),
00065     cam_subsampling_rate_(1),
00066     cam_binning_rate_(1),
00067     cam_sensor_scaling_rate_(1),
00068     bits_per_pixel_(8) {
00069   cam_aoi_.s32X = 0;
00070   cam_aoi_.s32Y = 0;
00071   cam_aoi_.s32Width = 640;
00072   cam_aoi_.s32Height = 480;
00073 };
00074 
00075 
00076 UEyeCamDriver::~UEyeCamDriver() {
00077   disconnectCam();
00078 };
00079 
00080 
00081 INT UEyeCamDriver::connectCam(int new_cam_ID) {
00082   INT is_err = IS_SUCCESS;
00083   int numCameras;
00084 
00085   // Terminate any existing opened cameras
00086   setStandbyMode();
00087 
00088   // Updates camera ID if specified.
00089   if (new_cam_ID >= 0) {
00090     cam_id_ = new_cam_ID;
00091   }
00092 
00093   // Query for number of connected cameras
00094   if ((is_err = is_GetNumberOfCameras(&numCameras)) != IS_SUCCESS) {
00095     ERROR_STREAM("Failed query for number of connected UEye cameras (" <<
00096       err2str(is_err) << ")");
00097     return is_err;
00098   } else if (numCameras < 1) {
00099     ERROR_STREAM("No UEye cameras are connected");
00100     return IS_NO_SUCCESS;
00101   } // NOTE: previously checked if ID < numCameras, but turns out that ID can be arbitrary
00102 
00103   // Attempt to open camera handle, and handle case where camera requires a
00104   // mandatory firmware upload
00105   cam_handle_ = (HIDS) cam_id_;
00106   if ((is_err = is_InitCamera(&cam_handle_, NULL)) == IS_STARTER_FW_UPLOAD_NEEDED) {
00107     INT uploadTimeMSEC = 25000;
00108     is_GetDuration (cam_handle_, IS_STARTER_FW_UPLOAD, &uploadTimeMSEC);
00109 
00110     INFO_STREAM("Uploading new firmware to UEye camera '" << cam_name_
00111       << "'; please wait for about " << uploadTimeMSEC/1000.0 << " seconds");
00112 
00113     // Attempt to re-open camera handle while triggering automatic firmware upload
00114     cam_handle_ = (HIDS) (((INT) cam_handle_) | IS_ALLOW_STARTER_FW_UPLOAD);
00115     is_err = is_InitCamera(&cam_handle_, NULL); // Will block for N seconds
00116   }
00117   if (is_err != IS_SUCCESS) {
00118     ERROR_STREAM("Could not open UEye camera ID " << cam_id_ <<
00119       " (" << err2str(is_err) << ")");
00120     return is_err;
00121   }
00122 
00123   // Set display mode to Device Independent Bitmap (DIB)
00124   is_err = is_SetDisplayMode(cam_handle_, IS_SET_DM_DIB);
00125 
00126   // Fetch sensor parameters
00127   is_err = is_GetSensorInfo(cam_handle_, &cam_sensor_info_);
00128 
00129   // Initialize local camera frame buffer
00130   reallocateCamBuffer();
00131 
00132   return is_err;
00133 };
00134 
00135 
00136 INT UEyeCamDriver::disconnectCam() {
00137   INT is_err = IS_SUCCESS;
00138 
00139   if (isConnected()) {
00140     setStandbyMode();
00141 
00142     // Release existing camera buffers
00143     if (cam_buffer_ != NULL) {
00144       is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
00145     }
00146     cam_buffer_ = NULL;
00147 
00148     // Release camera handle
00149     is_err = is_ExitCamera(cam_handle_);
00150     cam_handle_ = (HIDS) 0;
00151 
00152     DEBUG_STREAM("Disconnected UEye camera '" + cam_name_ + "'");
00153   }
00154 
00155   return is_err;
00156 };
00157 
00158 
00159 INT UEyeCamDriver::loadCamConfig(string filename) {
00160   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00161 
00162   INT is_err = IS_SUCCESS;
00163 
00164   // Convert filename to unicode, as requested by UEye API
00165   const wstring filenameU(filename.begin(), filename.end());
00166   if ((is_err = is_ParameterSet(cam_handle_, IS_PARAMETERSET_CMD_LOAD_FILE,
00167       (void*) filenameU.c_str(), 0)) != IS_SUCCESS) {
00168     WARN_STREAM("Could not load UEye camera '" << cam_name_
00169       << "' sensor parameters file " << filename << " (" << err2str(is_err) << ")");
00170     return is_err;
00171   } else {
00172     // Update the AOI and bits per pixel
00173     if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_GET_AOI,
00174         (void*) &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
00175       ERROR_STREAM("Could not retrieve Area Of Interest from UEye camera '" <<
00176           cam_name_ << "' (" << err2str(is_err) << ")");
00177       return is_err;
00178     }
00179     INT colorMode = is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE);
00180     if (colorMode == IS_CM_BGR8_PACKED || colorMode == IS_CM_RGB8_PACKED) {
00181       bits_per_pixel_ = 24;
00182     } else if (colorMode == IS_CM_MONO8 || colorMode == IS_CM_SENSOR_RAW8) {
00183       bits_per_pixel_ = 8;
00184     } else {
00185       WARN_STREAM("Current camera color mode is not supported by this wrapper;" <<
00186           "supported modes: {MONO8 | RGB8 | BAYER_RGGB8}; switching to RGB8 (24-bit)");
00187       if ((is_err = setColorMode("rgb8", false)) != IS_SUCCESS) return is_err;
00188     }
00189 
00190     reallocateCamBuffer();
00191 
00192     DEBUG_STREAM("Successfully loaded UEye camera '" << cam_name_
00193       << "'s sensor parameter file: " << filename);
00194   }
00195 
00196   return is_err;
00197 };
00198 
00199 
00200 INT UEyeCamDriver::setColorMode(string mode, bool reallocate_buffer) {
00201   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00202 
00203   INT is_err = IS_SUCCESS;
00204 
00205   // Stop capture to prevent access to memory buffer
00206   setStandbyMode();
00207 
00208   // Set to specified color mode
00209   if (mode == "rgb8") {
00210     if ((is_err = is_SetColorMode(cam_handle_, IS_CM_RGB8_PACKED)) != IS_SUCCESS) {
00211       ERROR_STREAM("Could not set color mode to RGB8 (" << err2str(is_err) << ")");
00212       return is_err;
00213     }
00214     bits_per_pixel_ = 24;
00215   } else if (mode == "bayer_rggb8") {
00216     if ((is_err = is_SetColorMode(cam_handle_, IS_CM_SENSOR_RAW8)) != IS_SUCCESS) {
00217       ERROR_STREAM("Could not set color mode to BAYER_RGGB8 (" << err2str(is_err) << ")");
00218       return is_err;
00219     }
00220     bits_per_pixel_ = 8;
00221   } else { // Default to MONO8
00222     if ((is_err = is_SetColorMode(cam_handle_, IS_CM_MONO8)) != IS_SUCCESS) {
00223       ERROR_STREAM("Could not set color mode to MONO8 (" << err2str(is_err) << ")");
00224       return is_err;
00225     }
00226     bits_per_pixel_ = 8;
00227   }
00228 
00229   DEBUG_STREAM("Updated color mode to " << mode);
00230 
00231   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00232 };
00233 
00234 
00235 INT UEyeCamDriver::setResolution(INT& image_width, INT& image_height,
00236     INT& image_left, INT& image_top, bool reallocate_buffer) {
00237   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00238 
00239   INT is_err = IS_SUCCESS;
00240 
00241   // Validate arguments
00242   CAP(image_width, 8, (INT) cam_sensor_info_.nMaxWidth);
00243   CAP(image_height, 4, (INT) cam_sensor_info_.nMaxHeight);
00244   if (image_left >= 0 && (int) cam_sensor_info_.nMaxWidth - image_width - image_left < 0) {
00245     WARN_STREAM("Cannot set image left index to " <<
00246         image_left << " with an image width of " <<
00247         image_width << " and sensor max width of " <<
00248         cam_sensor_info_.nMaxWidth);
00249     image_left = -1;
00250   }
00251   if (image_top >= 0 &&
00252       (int) cam_sensor_info_.nMaxHeight - image_height - image_top < 0) {
00253     WARN_STREAM("Cannot set image top index to " <<
00254         image_top << " with an image height of " <<
00255         image_height << " and sensor max height of " <<
00256         cam_sensor_info_.nMaxHeight);
00257     image_top = -1;
00258   }
00259   cam_aoi_.s32X = (image_left < 0) ?
00260       (cam_sensor_info_.nMaxWidth - image_width) / 2 : image_left;
00261   cam_aoi_.s32Y = (image_top < 0) ?
00262       (cam_sensor_info_.nMaxHeight - image_height) / 2 : image_top;
00263   cam_aoi_.s32Width = image_width;
00264   cam_aoi_.s32Height = image_height;
00265   if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_SET_AOI, &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
00266     ERROR_STREAM("Failed to set UEye camera sensor's Area Of Interest to " <<
00267       image_width << " x " << image_height <<
00268       " with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y << ")" );
00269     return is_err;
00270   }
00271 
00272   DEBUG_STREAM("Updated resolution to " << image_width << " x " << image_height <<
00273       " @ (" << image_left << ", " << image_top << ")");
00274 
00275   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00276 };
00277 
00278 
00279 INT UEyeCamDriver::setSubsampling(int& rate, bool reallocate_buffer) {
00280   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00281 
00282   INT is_err = IS_SUCCESS;
00283 
00284   // Stop capture to prevent access to memory buffer
00285   setStandbyMode();
00286 
00287   INT rate_flag;
00288   INT supportedRates;
00289 
00290   supportedRates = is_SetSubSampling(cam_handle_, IS_GET_SUPPORTED_SUBSAMPLING);
00291   switch (rate) {
00292     case 1:
00293       rate_flag = IS_SUBSAMPLING_DISABLE;
00294       break;
00295     case 2:
00296       rate_flag = IS_SUBSAMPLING_2X;
00297       break;
00298     case 4:
00299       rate_flag = IS_SUBSAMPLING_4X;
00300       break;
00301     case 8:
00302       rate_flag = IS_SUBSAMPLING_8X;
00303       break;
00304     case 16:
00305       rate_flag = IS_SUBSAMPLING_16X;
00306       break;
00307     default:
00308       WARN_STREAM("Invalid or unsupported subsampling rate: " << rate << ", resetting to 1X");
00309       rate = 1;
00310       rate_flag = IS_SUBSAMPLING_DISABLE;
00311       break;
00312   }
00313 
00314   if ((supportedRates & rate_flag) == rate_flag) {
00315     if ((is_err = is_SetSubSampling(cam_handle_, rate_flag)) != IS_SUCCESS) {
00316       ERROR_STREAM("Could not set subsampling rate to " << rate << "X (" << err2str(is_err) << ")");
00317       return is_err;
00318     }
00319   } else {
00320     WARN_STREAM("Camera does not support requested sampling rate of " << rate);
00321 
00322     // Query current rate
00323     INT currRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
00324     if (currRate == IS_SUBSAMPLING_DISABLE) { rate = 1; }
00325     else if (currRate == IS_SUBSAMPLING_2X) { rate = 2; }
00326     else if (currRate == IS_SUBSAMPLING_4X) { rate = 4; }
00327     else if (currRate == IS_SUBSAMPLING_8X) { rate = 8; }
00328     else if (currRate == IS_SUBSAMPLING_16X) { rate = 16; }
00329     else {
00330       WARN_STREAM("Camera has unsupported sampling rate (" << currRate << "), resetting to 1X");
00331       if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
00332         ERROR_STREAM("Could not set subsampling rate to 1X (" << err2str(is_err) << ")");
00333         return is_err;
00334       }
00335     }
00336     return IS_SUCCESS;
00337   }
00338 
00339   DEBUG_STREAM("Updated subsampling rate to " << rate << "X");
00340 
00341   cam_subsampling_rate_ = rate;
00342 
00343   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00344 };
00345 
00346 
00347 INT UEyeCamDriver::setBinning(int& rate, bool reallocate_buffer) {
00348   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00349 
00350   INT is_err = IS_SUCCESS;
00351 
00352   // Stop capture to prevent access to memory buffer
00353   setStandbyMode();
00354 
00355   INT rate_flag;
00356   INT supportedRates;
00357 
00358   supportedRates = is_SetBinning(cam_handle_, IS_GET_SUPPORTED_BINNING);
00359   switch (rate) {
00360     case 1:
00361       rate_flag = IS_BINNING_DISABLE;
00362       break;
00363     case 2:
00364       rate_flag = IS_BINNING_2X;
00365       break;
00366     case 4:
00367       rate_flag = IS_BINNING_4X;
00368       break;
00369     case 8:
00370       rate_flag = IS_BINNING_8X;
00371       break;
00372     case 16:
00373       rate_flag = IS_BINNING_16X;
00374       break;
00375     default:
00376       WARN_STREAM("Invalid or unsupported binning rate: " << rate << ", resetting to 1X");
00377       rate = 1;
00378       rate_flag = IS_BINNING_DISABLE;
00379       break;
00380   }
00381 
00382   if ((supportedRates & rate_flag) == rate_flag) {
00383     if ((is_err = is_SetBinning(cam_handle_, rate_flag)) != IS_SUCCESS) {
00384       ERROR_STREAM("Could not set binning rate to " << rate << "X (" << err2str(is_err) << ")");
00385       return is_err;
00386     }
00387   } else {
00388     WARN_STREAM("Camera does not support requested binning rate of " << rate);
00389 
00390     // Query current rate
00391     INT currRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
00392     if (currRate == IS_BINNING_DISABLE) { rate = 1; }
00393     else if (currRate == IS_BINNING_2X) { rate = 2; }
00394     else if (currRate == IS_BINNING_4X) { rate = 4; }
00395     else if (currRate == IS_BINNING_8X) { rate = 8; }
00396     else if (currRate == IS_BINNING_16X) { rate = 16; }
00397     else {
00398       WARN_STREAM("Camera has unsupported binning rate (" << currRate << "), resetting to 1X");
00399       if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
00400         ERROR_STREAM("Could not set binning rate to 1X (" << err2str(is_err) << ")");
00401         return is_err;
00402       }
00403     }
00404     return IS_SUCCESS;
00405   }
00406 
00407   DEBUG_STREAM("Updated binning rate to " << rate << "X");
00408 
00409   cam_binning_rate_ = rate;
00410 
00411   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00412 };
00413 
00414 
00415 INT UEyeCamDriver::setSensorScaling(double& rate, bool reallocate_buffer) {
00416   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00417 
00418   INT is_err = IS_SUCCESS;
00419 
00420   // Stop capture to prevent access to memory buffer
00421   setStandbyMode();
00422 
00423   SENSORSCALERINFO sensorScalerInfo;
00424   is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
00425   if (is_err == IS_NOT_SUPPORTED) {
00426     WARN_STREAM("Internal image scaling is not supported by camera");
00427     rate = 1.0;
00428     cam_sensor_scaling_rate_ = 1.0;
00429     return IS_SUCCESS;
00430   } else if (is_err != IS_SUCCESS) {
00431     ERROR_STREAM("Could not obtain supported internal image scaling information (" <<
00432         err2str(is_err) << ")");
00433     rate = 1.0;
00434     cam_sensor_scaling_rate_ = 1.0;
00435     return is_err;
00436   } else {
00437     if (rate < sensorScalerInfo.dblMinFactor || rate > sensorScalerInfo.dblMaxFactor) {
00438       WARN_STREAM("Requested internal image scaling rate of " << rate <<
00439           " is not within supported bounds of [" << sensorScalerInfo.dblMinFactor <<
00440           ", " << sensorScalerInfo.dblMaxFactor << "]; not updating current rate of " <<
00441           sensorScalerInfo.dblCurrFactor);
00442       rate = sensorScalerInfo.dblCurrFactor;
00443       return IS_SUCCESS;
00444     }
00445   }
00446 
00447   if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
00448     WARN_STREAM("Could not set internal image scaling rate to " << rate << "X (" <<
00449         err2str(is_err) << "); resetting to 1X");
00450     rate = 1.0;
00451     if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
00452       ERROR_STREAM("Could not set internal image scaling rate to 1X (" << err2str(is_err) << ")");
00453       return is_err;
00454     }
00455   }
00456 
00457   DEBUG_STREAM("Updated internal image scaling rate to " << rate << "X");
00458 
00459   cam_sensor_scaling_rate_ = rate;
00460 
00461   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00462 };
00463 
00464 
00465 INT UEyeCamDriver::setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
00466     INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost) {
00467   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00468 
00469   INT is_err = IS_SUCCESS;
00470 
00471   // Validate arguments
00472   CAP(master_gain_prc, 0, 100);
00473   CAP(red_gain_prc, 0, 100);
00474   CAP(green_gain_prc, 0, 100);
00475   CAP(blue_gain_prc, 0, 100);
00476 
00477   double pval1 = 0, pval2 = 0;
00478 
00479   if (auto_gain) {
00480     // Set auto gain
00481     pval1 = 1;
00482     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
00483         &pval1, &pval2)) != IS_SUCCESS) {
00484       if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
00485           &pval1, &pval2)) != IS_SUCCESS) {
00486         WARN_STREAM("Auto gain mode is not supported for UEye camera '" <<
00487             cam_name_ << "' (" << err2str(is_err) << ")");
00488         auto_gain = false;
00489       }
00490     }
00491   } else {
00492     // Disable auto gain
00493     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
00494         &pval1, &pval2)) != IS_SUCCESS) {
00495       if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
00496           &pval1, &pval2)) != IS_SUCCESS) {
00497         DEBUG_STREAM("Auto gain mode is not supported for UEye camera '" <<
00498             cam_name_ << "' (" << err2str(is_err) << ")");
00499       }
00500     }
00501 
00502     // Set gain boost
00503     if (is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
00504       gain_boost = false;
00505     } else {
00506       if ((is_err = is_SetGainBoost(cam_handle_,
00507           (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF))
00508           != IS_SUCCESS) {
00509         WARN_STREAM("Failed to " << ((gain_boost) ? "enable" : "disable") <<
00510             " gain boost for UEye camera '" + cam_name_ + "'");
00511       }
00512     }
00513 
00514     // Set manual gain parameters
00515     if ((is_err = is_SetHardwareGain(cam_handle_, master_gain_prc,
00516         red_gain_prc, green_gain_prc, blue_gain_prc)) != IS_SUCCESS) {
00517       WARN_STREAM("Failed to set manual gains (master: " << master_gain_prc <<
00518           "; red: " << red_gain_prc << "; green: " << green_gain_prc <<
00519           "; blue: " << blue_gain_prc << ") for UEye camera '" + cam_name_ + "'");
00520     }
00521   }
00522 
00523   if (auto_gain) {
00524     DEBUG_STREAM("Updated gain: auto");
00525   } else {
00526     DEBUG_STREAM("Updated gain: manual" <<
00527         "\n   - master gain: " << master_gain_prc <<
00528         "\n   - red gain: " << red_gain_prc <<
00529         "\n   - green gain: " << green_gain_prc <<
00530         "\n   - blue gain: " << blue_gain_prc <<
00531         "\n   - gain boost: " << gain_boost);
00532   }
00533 
00534   return is_err;
00535 };
00536 
00537 
00538 INT UEyeCamDriver::setExposure(bool& auto_exposure, double& exposure_ms) {
00539   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00540 
00541   INT is_err = IS_SUCCESS;
00542 
00543   double minExposure, maxExposure;
00544 
00545   // Set auto exposure
00546   double pval1 = auto_exposure, pval2 = 0;
00547   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER,
00548       &pval1, &pval2)) != IS_SUCCESS) {
00549     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SHUTTER,
00550         &pval1, &pval2)) != IS_SUCCESS) {
00551       WARN_STREAM("Auto exposure mode is not supported for UEye camera '" <<
00552           cam_name_ << "' (" << err2str(is_err) << ")");
00553       auto_exposure = false;
00554     }
00555   }
00556 
00557   // Set manual exposure timing
00558   if (!auto_exposure) {
00559     // Make sure that user-requested exposure rate is achievable
00560     if (((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN,
00561         (void*) &minExposure, sizeof(minExposure))) != IS_SUCCESS) ||
00562         ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX,
00563         (void*) &maxExposure, sizeof(maxExposure))) != IS_SUCCESS)) {
00564       ERROR_STREAM("Failed to query valid exposure range from UEye camera '" << cam_name_ << "'");
00565       return is_err;
00566     }
00567     CAP(exposure_ms, minExposure, maxExposure);
00568 
00569     // Update exposure
00570     if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_SET_EXPOSURE,
00571         (void*) &(exposure_ms), sizeof(exposure_ms))) != IS_SUCCESS) {
00572       ERROR_STREAM("Failed to set exposure to " << exposure_ms <<
00573           " ms for UEye camera '" << cam_name_ << "'");
00574       return is_err;
00575     }
00576   }
00577 
00578   DEBUG_STREAM("Updated exposure: " << ((auto_exposure) ? "auto" : to_string(exposure_ms)) <<
00579       " ms");
00580 
00581   return is_err;
00582 };
00583 
00584 
00585 INT UEyeCamDriver::setWhiteBalance(bool& auto_white_balance, INT& red_offset,
00586     INT& blue_offset) {
00587   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00588 
00589   INT is_err = IS_SUCCESS;
00590 
00591   CAP(red_offset, -50, 50);
00592   CAP(blue_offset, -50, 50);
00593 
00594   // Set auto white balance mode and parameters
00595   double pval1 = auto_white_balance, pval2 = 0;
00596   // TODO: 9 bug: enabling auto white balance does not seem to have an effect; in ueyedemo it seems to change R/G/B gains automatically
00597   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_WHITEBALANCE,
00598       &pval1, &pval2)) != IS_SUCCESS) {
00599     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_ONCE,
00600         &pval1, &pval2)) != IS_SUCCESS) {
00601       WARN_STREAM("Auto white balance mode is not supported for UEye camera '" <<
00602         cam_name_ << "' (" << err2str(is_err) << ")");
00603       auto_white_balance = false;
00604     }
00605   }
00606   if (auto_white_balance) {
00607     pval1 = red_offset;
00608     pval2 = blue_offset;
00609     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_OFFSET,
00610         &pval1, &pval2)) != IS_SUCCESS) {
00611       WARN_STREAM("Failed to set white balance red/blue offsets to " <<
00612           red_offset << " / " << blue_offset <<
00613           " for UEye camera '" << cam_name_ << "'");
00614     }
00615   }
00616 
00617   DEBUG_STREAM("Updated white balance: " << ((auto_white_balance) ? "auto" : "manual") <<
00618   "\n   - red offset: " << red_offset <<
00619   "\n   - blue offset: " << blue_offset);
00620 
00621   return is_err;
00622 };
00623 
00624 
00625 INT UEyeCamDriver::setFrameRate(bool& auto_frame_rate, double& frame_rate_hz) {
00626   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00627 
00628   INT is_err = IS_SUCCESS;
00629 
00630   double pval1 = 0, pval2 = 0;
00631   double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
00632 
00633   // Make sure that auto shutter is enabled before enabling auto frame rate
00634   bool autoShutterOn = false;
00635   is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
00636   autoShutterOn |= (pval1 != 0);
00637   is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
00638   autoShutterOn |= (pval1 != 0);
00639   if (!autoShutterOn) {
00640     auto_frame_rate = false;
00641   }
00642 
00643   // Set frame rate / auto
00644   pval1 = auto_frame_rate;
00645   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE,
00646       &pval1, &pval2)) != IS_SUCCESS) {
00647     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_FRAMERATE,
00648         &pval1, &pval2)) != IS_SUCCESS) {
00649       WARN_STREAM("Auto frame rate mode is not supported for UEye camera '" <<
00650           cam_name_ << "' (" << err2str(is_err) << ")");
00651       auto_frame_rate = false;
00652     }
00653   }
00654   if (!auto_frame_rate) {
00655     // Make sure that user-requested frame rate is achievable
00656     if ((is_err = is_GetFrameTimeRange(cam_handle_, &minFrameTime,
00657         &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
00658       ERROR_STREAM("Failed to query valid frame rate range from UEye camera '" << cam_name_ << "'");
00659       return is_err;
00660     }
00661     CAP(frame_rate_hz, 1.0/maxFrameTime, 1.0/minFrameTime);
00662 
00663     // Update frame rate
00664     if ((is_err = is_SetFrameRate(cam_handle_, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
00665       ERROR_STREAM("Failed to set frame rate to " << frame_rate_hz <<
00666           " MHz for UEye camera '" << cam_name_ << "'");
00667       return is_err;
00668     } else if (frame_rate_hz != newFrameRate) {
00669       frame_rate_hz = newFrameRate;
00670     }
00671   }
00672 
00673   DEBUG_STREAM("Updated frame rate: " << ((auto_frame_rate) ? "auto" : to_string(frame_rate_hz)) << " Hz");
00674 
00675   return is_err;
00676 };
00677 
00678 
00679 INT UEyeCamDriver::setPixelClockRate(INT& clock_rate_mhz) {
00680   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00681 
00682   INT is_err = IS_SUCCESS;
00683 
00684   UINT pixelClockRange[3];
00685   ZeroMemory(pixelClockRange, sizeof(pixelClockRange));
00686 
00687   if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_RANGE,
00688       (void*) pixelClockRange, sizeof(pixelClockRange))) != IS_SUCCESS) {
00689     ERROR_STREAM("Failed to query pixel clock range from UEye camera '" <<
00690         cam_name_ << "'");
00691     return is_err;
00692   }
00693   CAP(clock_rate_mhz, (int) pixelClockRange[0], (int) pixelClockRange[1]);
00694   if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_SET,
00695       (void*) &(clock_rate_mhz), sizeof(clock_rate_mhz))) != IS_SUCCESS) {
00696     ERROR_STREAM("Failed to set pixel clock to " << clock_rate_mhz <<
00697         "MHz for UEye camera '" << cam_name_ << "'");
00698     return is_err;
00699   }
00700 
00701   DEBUG_STREAM("Updated pixel clock: " << clock_rate_mhz << " MHz");
00702 
00703   return IS_SUCCESS;
00704 };
00705 
00706 
00707 INT UEyeCamDriver::setFlashParams(INT& delay_us, UINT& duration_us) {
00708   INT is_err = IS_SUCCESS;
00709 
00710   // Make sure parameters are within range supported by camera
00711   IO_FLASH_PARAMS minFlashParams, maxFlashParams, newFlashParams;
00712   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MIN,
00713       (void*) &minFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00714     ERROR_STREAM("Could not retrieve flash parameter info (min) for UEye camera '" <<
00715         cam_name_ << "' (" << err2str(is_err) << ")");
00716     return is_err;
00717   }
00718   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MAX,
00719       (void*) &maxFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00720     ERROR_STREAM("Could not retrieve flash parameter info (max) for UEye camera '" <<
00721         cam_name_ << "' (" << err2str(is_err) << ")");
00722     return is_err;
00723   }
00724   delay_us = (delay_us < minFlashParams.s32Delay) ? minFlashParams.s32Delay :
00725       ((delay_us > maxFlashParams.s32Delay) ? maxFlashParams.s32Delay : delay_us);
00726   duration_us = (duration_us < minFlashParams.u32Duration && duration_us != 0) ? minFlashParams.u32Duration :
00727       ((duration_us > maxFlashParams.u32Duration) ? maxFlashParams.u32Duration : duration_us);
00728   newFlashParams.s32Delay = delay_us;
00729   newFlashParams.u32Duration = duration_us;
00730   // WARNING: Setting s32Duration to 0, according to documentation, means
00731   //          setting duration to total exposure time. If non-ext-triggered
00732   //          camera is operating at fastest grab rate, then the resulting
00733   //          flash signal will APPEAR as active LO when set to active HIGH,
00734   //          and vice versa. This is why the duration is set manually.
00735   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_PARAMS,
00736       (void*) &newFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00737     ERROR_STREAM("Could not set flash parameter info for UEye camera '" <<
00738         cam_name_ << "' (" << err2str(is_err) << ")");
00739     return is_err;
00740   }
00741 
00742   return is_err;
00743 };
00744 
00745 
00746 INT UEyeCamDriver::setFreeRunMode() {
00747   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00748 
00749   INT is_err = IS_SUCCESS;
00750 
00751   if (!freeRunModeActive()) {
00752     setStandbyMode(); // No need to check for success
00753 
00754     // Set the flash to a high active pulse for each image in the trigger mode
00755     INT flash_delay = 0;
00756     UINT flash_duration = 1000;
00757     setFlashParams(flash_delay, flash_duration);
00758     UINT nMode = IO_FLASH_MODE_FREERUN_HI_ACTIVE;
00759     if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
00760         (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
00761       ERROR_STREAM("Could not set free-run active-low flash output for UEye camera '" <<
00762           cam_name_ << "' (" << err2str(is_err) << ")");
00763       return is_err;
00764     }
00765 
00766     if ((is_err = is_EnableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00767       ERROR_STREAM("Could not enable frame event for UEye camera '" <<
00768           cam_name_ << "' (" << err2str(is_err) << ")");
00769       return is_err;
00770     }
00771     if ((is_err = is_CaptureVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00772       ERROR_STREAM("Could not start free-run live video mode on UEye camera '" <<
00773           cam_name_ << "' (" << err2str(is_err) << ")");
00774       return is_err;
00775     }
00776     DEBUG_STREAM("Started live video mode on UEye camera '" + cam_name_ + "'");
00777   }
00778 
00779   return is_err;
00780 };
00781 
00782 
00783 INT UEyeCamDriver::setExtTriggerMode() {
00784   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00785 
00786   INT is_err = IS_SUCCESS;
00787 
00788   if (!extTriggerModeActive()) {
00789     setStandbyMode(); // No need to check for success
00790 
00791     if ((is_err = is_EnableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00792       ERROR_STREAM("Could not enable frame event for UEye camera '" <<
00793           cam_name_ << "' (" << err2str(is_err) << ")");
00794       return is_err;
00795     }
00796 
00797     if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_HI_LO)) != IS_SUCCESS) {
00798       ERROR_STREAM("Could not enable falling-edge external trigger mode on UEye camera '" <<
00799           cam_name_ << "' (" << err2str(is_err) << ")");
00800       return is_err;
00801     }
00802     if ((is_err = is_CaptureVideo(cam_handle_, IS_DONT_WAIT)) != IS_SUCCESS) {
00803       ERROR_STREAM("Could not start external trigger live video mode on UEye camera '" <<
00804           cam_name_ << "' (" << err2str(is_err) << ")");
00805       return is_err;
00806     }
00807     DEBUG_STREAM("Started falling-edge external trigger live video mode on UEye camera '" + cam_name_ + "'");
00808   }
00809 
00810   return is_err;
00811 };
00812 
00813 INT UEyeCamDriver::setMirrorUpsideDown(bool flip_horizontal){
00814   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00815 
00816   INT is_err = IS_SUCCESS;
00817   if(flip_horizontal)
00818      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,1,0);
00819   else
00820      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,0,0);
00821 
00822   return is_err;
00823 }
00824 
00825 INT UEyeCamDriver::setMirrorLeftRight(bool flip_vertical){
00826   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00827 
00828   INT is_err = IS_SUCCESS;
00829   if(flip_vertical)
00830      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,1,0);
00831   else
00832      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,0,0);
00833 
00834   return is_err;
00835 }
00836 
00837 INT UEyeCamDriver::setStandbyMode() {
00838   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00839 
00840   INT is_err = IS_SUCCESS;
00841 
00842   if (extTriggerModeActive()) {
00843       if ((is_err = is_DisableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00844         ERROR_STREAM("Could not disable frame event for UEye camera '" <<
00845             cam_name_ << "' (" << err2str(is_err) << ")");
00846         return is_err;
00847       }
00848       if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_OFF)) != IS_SUCCESS) {
00849         ERROR_STREAM("Could not disable external trigger mode on UEye camera '" <<
00850             cam_name_ << "' (" << err2str(is_err) << ")");
00851         return is_err;
00852       }
00853       is_SetExternalTrigger(cam_handle_, IS_GET_TRIGGER_STATUS); // documentation seems to suggest that this is needed to disable external trigger mode (to go into free-run mode)
00854       if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00855         ERROR_STREAM("Could not stop live video mode on UEye camera '" <<
00856             cam_name_ << "' (" << err2str(is_err) << ")");
00857         return is_err;
00858       }
00859       DEBUG_STREAM("Stopped external trigger mode on UEye camera '" + cam_name_ + "'");
00860   } else if (freeRunModeActive()) {
00861     UINT nMode = IO_FLASH_MODE_OFF;
00862     if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
00863         (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
00864       ERROR_STREAM("Could not disable flash output for UEye camera '" <<
00865           cam_name_ << "' (" << err2str(is_err) << ")");
00866       return is_err;
00867     }
00868     if ((is_err = is_DisableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00869       ERROR_STREAM("Could not disable frame event for UEye camera '" <<
00870           cam_name_ << "' (" << err2str(is_err) << ")");
00871       return is_err;
00872     }
00873     if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00874       ERROR_STREAM("Could not stop live video mode on UEye camera '" <<
00875           cam_name_ << "' (" << err2str(is_err) << ")");
00876       return is_err;
00877     }
00878     DEBUG_STREAM("Stopped free-run live video mode on UEye camera '" + cam_name_ + "'");
00879   }
00880   if ((is_err = is_CameraStatus(cam_handle_, IS_STANDBY, IS_GET_STATUS)) != IS_SUCCESS) {
00881     ERROR_STREAM("Could not set standby mode for UEye camera '" <<
00882         cam_name_ << "' (" << err2str(is_err) << ")");
00883     return is_err;
00884   }
00885 
00886   return is_err;
00887 };
00888 
00889 
00890 const char* UEyeCamDriver::processNextFrame(INT timeout_ms) {
00891   if (!freeRunModeActive() && !extTriggerModeActive()) return NULL;
00892 
00893   INT is_err = IS_SUCCESS;
00894 
00895   // Wait for frame event
00896   if ((is_err = is_WaitEvent(cam_handle_, IS_SET_EVENT_FRAME,
00897         timeout_ms)) != IS_SUCCESS) {
00898     ERROR_STREAM("Failed to acquire image from UEye camera '" <<
00899           cam_name_ << "' (" << err2str(is_err) << ")");
00900     return NULL;
00901   }
00902 
00903   return cam_buffer_;
00904 };
00905 
00906 
00907 INT UEyeCamDriver::reallocateCamBuffer() {
00908   INT is_err = IS_SUCCESS;
00909 
00910   // Stop capture to prevent access to memory buffer
00911   setStandbyMode();
00912 
00913   if (cam_buffer_ != NULL) {
00914     is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
00915     cam_buffer_ = NULL;
00916   }
00917   if ((is_err = is_AllocImageMem(cam_handle_,
00918       cam_aoi_.s32Width / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_),
00919       cam_aoi_.s32Height / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_),
00920       bits_per_pixel_, &cam_buffer_, &cam_buffer_id_)) != IS_SUCCESS) {
00921     ERROR_STREAM("Failed to allocate " <<
00922         cam_aoi_.s32Width / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_) <<
00923       " x " <<
00924       cam_aoi_.s32Height / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_) <<
00925       " image buffer");
00926     return is_err;
00927   }
00928   if ((is_err = is_SetImageMem(cam_handle_, cam_buffer_, cam_buffer_id_)) != IS_SUCCESS) {
00929     ERROR_STREAM("Failed to associate an image buffer to the UEye camera driver");
00930     return is_err;
00931   }
00932   if ((is_err = is_GetImageMemPitch(cam_handle_, &cam_buffer_pitch_)) != IS_SUCCESS) {
00933     ERROR_STREAM("Failed to query UEye camera buffer's pitch (a.k.a. stride)");
00934     return is_err;
00935   }
00936   cam_buffer_size_ = cam_buffer_pitch_ * cam_aoi_.s32Height /
00937       (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_);
00938   DEBUG_STREAM("Allocate internal memory - width: " <<
00939       cam_aoi_.s32Width / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_) <<
00940       "; height: " <<
00941       cam_aoi_.s32Height / (cam_sensor_scaling_rate_ * cam_subsampling_rate_ * cam_binning_rate_) <<
00942       "; fetched pitch: " << cam_buffer_pitch_ << "; expected bpp: " << bits_per_pixel_ <<
00943       "; total size: " << cam_buffer_size_);
00944 
00945   return is_err;
00946 };
00947 
00948 
00949 const char* UEyeCamDriver::err2str(INT error) {
00950 #define CASE(s) case s: return #s; break
00951   switch (error) {
00952   CASE(IS_NO_SUCCESS);
00953   CASE(IS_SUCCESS);
00954   CASE(IS_INVALID_CAMERA_HANDLE);
00955   CASE(IS_IO_REQUEST_FAILED);
00956   CASE(IS_CANT_OPEN_DEVICE);
00957   CASE(IS_CANT_OPEN_REGISTRY);
00958   CASE(IS_CANT_READ_REGISTRY);
00959   CASE(IS_NO_IMAGE_MEM_ALLOCATED);
00960   CASE(IS_CANT_CLEANUP_MEMORY);
00961   CASE(IS_CANT_COMMUNICATE_WITH_DRIVER);
00962   CASE(IS_FUNCTION_NOT_SUPPORTED_YET);
00963   CASE(IS_INVALID_CAPTURE_MODE);
00964   CASE(IS_INVALID_MEMORY_POINTER);
00965   CASE(IS_FILE_WRITE_OPEN_ERROR);
00966   CASE(IS_FILE_READ_OPEN_ERROR);
00967   CASE(IS_FILE_READ_INVALID_BMP_ID);
00968   CASE(IS_FILE_READ_INVALID_BMP_SIZE);
00969   CASE(IS_NO_ACTIVE_IMG_MEM);
00970   CASE(IS_SEQUENCE_LIST_EMPTY);
00971   CASE(IS_CANT_ADD_TO_SEQUENCE);
00972   CASE(IS_SEQUENCE_BUF_ALREADY_LOCKED);
00973   CASE(IS_INVALID_DEVICE_ID);
00974   CASE(IS_INVALID_BOARD_ID);
00975   CASE(IS_ALL_DEVICES_BUSY);
00976   CASE(IS_TIMED_OUT);
00977   CASE(IS_NULL_POINTER);
00978   CASE(IS_INVALID_PARAMETER);
00979   CASE(IS_OUT_OF_MEMORY);
00980   CASE(IS_ACCESS_VIOLATION);
00981   CASE(IS_NO_USB20);
00982   CASE(IS_CAPTURE_RUNNING);
00983   CASE(IS_IMAGE_NOT_PRESENT);
00984   CASE(IS_TRIGGER_ACTIVATED);
00985   CASE(IS_CRC_ERROR);
00986   CASE(IS_NOT_YET_RELEASED);
00987   CASE(IS_WAITING_FOR_KERNEL);
00988   CASE(IS_NOT_SUPPORTED);
00989   CASE(IS_TRIGGER_NOT_ACTIVATED);
00990   CASE(IS_OPERATION_ABORTED);
00991   CASE(IS_BAD_STRUCTURE_SIZE);
00992   CASE(IS_INVALID_BUFFER_SIZE);
00993   CASE(IS_INVALID_PIXEL_CLOCK);
00994   CASE(IS_INVALID_EXPOSURE_TIME);
00995   CASE(IS_AUTO_EXPOSURE_RUNNING);
00996   CASE(IS_CANNOT_CREATE_BB_SURF);
00997   CASE(IS_CANNOT_CREATE_BB_MIX);
00998   CASE(IS_BB_OVLMEM_NULL);
00999   CASE(IS_CANNOT_CREATE_BB_OVL);
01000   CASE(IS_NOT_SUPP_IN_OVL_SURF_MODE);
01001   CASE(IS_INVALID_SURFACE);
01002   CASE(IS_SURFACE_LOST);
01003   CASE(IS_RELEASE_BB_OVL_DC);
01004   CASE(IS_BB_TIMER_NOT_CREATED);
01005   CASE(IS_BB_OVL_NOT_EN);
01006   CASE(IS_ONLY_IN_BB_MODE);
01007   CASE(IS_INVALID_COLOR_FORMAT);
01008   CASE(IS_INVALID_WB_BINNING_MODE);
01009   CASE(IS_INVALID_I2C_DEVICE_ADDRESS);
01010   CASE(IS_COULD_NOT_CONVERT);
01011   CASE(IS_TRANSFER_ERROR);
01012   CASE(IS_PARAMETER_SET_NOT_PRESENT);
01013   CASE(IS_INVALID_CAMERA_TYPE);
01014   CASE(IS_INVALID_HOST_IP_HIBYTE);
01015   CASE(IS_CM_NOT_SUPP_IN_CURR_DISPLAYMODE);
01016   CASE(IS_NO_IR_FILTER);
01017   CASE(IS_STARTER_FW_UPLOAD_NEEDED);
01018   CASE(IS_DR_LIBRARY_NOT_FOUND);
01019   CASE(IS_DR_DEVICE_OUT_OF_MEMORY);
01020   CASE(IS_DR_CANNOT_CREATE_SURFACE);
01021   CASE(IS_DR_CANNOT_CREATE_VERTEX_BUFFER);
01022   CASE(IS_DR_CANNOT_CREATE_TEXTURE);
01023   CASE(IS_DR_CANNOT_LOCK_OVERLAY_SURFACE);
01024   CASE(IS_DR_CANNOT_UNLOCK_OVERLAY_SURFACE);
01025   CASE(IS_DR_CANNOT_GET_OVERLAY_DC);
01026   CASE(IS_DR_CANNOT_RELEASE_OVERLAY_DC);
01027   CASE(IS_DR_DEVICE_CAPS_INSUFFICIENT);
01028   CASE(IS_INCOMPATIBLE_SETTING);
01029   CASE(IS_DR_NOT_ALLOWED_WHILE_DC_IS_ACTIVE);
01030   CASE(IS_DEVICE_ALREADY_PAIRED);
01031   CASE(IS_SUBNETMASK_MISMATCH);
01032   CASE(IS_SUBNET_MISMATCH);
01033   CASE(IS_INVALID_IP_CONFIGURATION);
01034   CASE(IS_DEVICE_NOT_COMPATIBLE);
01035   CASE(IS_NETWORK_FRAME_SIZE_INCOMPATIBLE);
01036   CASE(IS_NETWORK_CONFIGURATION_INVALID);
01037   CASE(IS_ERROR_CPU_IDLE_STATES_CONFIGURATION);
01038   default:
01039     return "UNKNOWN ERROR";
01040     break;
01041   }
01042   return "UNKNOWN ERROR";
01043 #undef CASE
01044 };
01045 
01046 
01047 }; // namespace ueye_cam


ueye_cam
Author(s): Anqi Xu
autogenerated on Mon Oct 6 2014 08:20:41