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-2016, Anqi Xu and contributors
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 // Note that all of these default settings will be overwritten
00058 // by syncCamConfig() during connectCam()
00059 UEyeCamDriver::UEyeCamDriver(int cam_ID, string cam_name):
00060     cam_handle_((HIDS) 0),
00061     cam_buffer_(NULL),
00062     cam_buffer_id_(0),
00063     cam_buffer_pitch_(0),
00064     cam_buffer_size_(0),
00065     cam_name_(cam_name),
00066     cam_id_(cam_ID),
00067     cam_subsampling_rate_(1),
00068     cam_binning_rate_(1),
00069     cam_sensor_scaling_rate_(1),
00070     color_mode_(IS_CM_MONO8),
00071     bits_per_pixel_(8) {
00072   cam_aoi_.s32X = 0;
00073   cam_aoi_.s32Y = 0;
00074   cam_aoi_.s32Width = 640;
00075   cam_aoi_.s32Height = 480;
00076 }
00077 
00078 
00079 UEyeCamDriver::~UEyeCamDriver() {
00080   disconnectCam();
00081 }
00082 
00083 
00084 INT UEyeCamDriver::connectCam(int new_cam_ID) {
00085   INT is_err = IS_SUCCESS;
00086   int numCameras;
00087 
00088   // Terminate any existing opened cameras
00089   setStandbyMode();
00090 
00091   // Updates camera ID if specified.
00092   if (new_cam_ID >= 0) {
00093     cam_id_ = new_cam_ID;
00094   }
00095 
00096   // Query for number of connected cameras
00097   if ((is_err = is_GetNumberOfCameras(&numCameras)) != IS_SUCCESS) {
00098     ERROR_STREAM("Failed query for number of connected UEye cameras (" <<
00099       err2str(is_err) << ")");
00100     return is_err;
00101   } else if (numCameras < 1) {
00102     ERROR_STREAM("No UEye cameras are connected\n");
00103     ERROR_STREAM("Hint: make sure that the IDS camera daemon (/etc/init.d/ueyeusbdrc) is running\n");
00104     return IS_NO_SUCCESS;
00105   } // NOTE: previously checked if ID < numCameras, but turns out that ID can be arbitrary
00106 
00107   // Attempt to open camera handle, and handle case where camera requires a
00108   // mandatory firmware upload
00109   cam_handle_ = (HIDS) cam_id_;
00110   if ((is_err = is_InitCamera(&cam_handle_, NULL)) == IS_STARTER_FW_UPLOAD_NEEDED) {
00111     INT uploadTimeMSEC = 25000;
00112     is_GetDuration (cam_handle_, IS_STARTER_FW_UPLOAD, &uploadTimeMSEC);
00113 
00114     INFO_STREAM("Uploading new firmware to [" << cam_name_
00115       << "]; please wait for about " << uploadTimeMSEC/1000.0 << " seconds");
00116 
00117     // Attempt to re-open camera handle while triggering automatic firmware upload
00118     cam_handle_ = (HIDS) (((INT) cam_handle_) | IS_ALLOW_STARTER_FW_UPLOAD);
00119     is_err = is_InitCamera(&cam_handle_, NULL); // Will block for N seconds
00120   }
00121   if (is_err != IS_SUCCESS) {
00122     ERROR_STREAM("Could not open UEye camera ID " << cam_id_ <<
00123       " (" << err2str(is_err) << ")");
00124     return is_err;
00125   }
00126 
00127   // Set display mode to Device Independent Bitmap (DIB)
00128   is_err = is_SetDisplayMode(cam_handle_, IS_SET_DM_DIB);
00129   if (is_err != IS_SUCCESS) {
00130     ERROR_STREAM("UEye camera ID " << cam_id_ <<
00131       " does not support Device Independent Bitmap mode;" <<
00132       " driver wrapper not compatible with OpenGL/DirectX modes (" << err2str(is_err) << ")");
00133     return is_err;
00134   }
00135 
00136   // Fetch sensor parameters
00137   is_err = is_GetSensorInfo(cam_handle_, &cam_sensor_info_);
00138   if (is_err != IS_SUCCESS) {
00139     ERROR_STREAM("Could not poll sensor information for [" << cam_name_ <<
00140       "] (" << err2str(is_err) << ")");
00141     return is_err;
00142   }
00143 
00144   // Validate camera's configuration to ensure compatibility with driver wrapper
00145   // (note that this function also initializes the internal frame buffer)
00146   if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
00147 
00148   DEBUG_STREAM("Connected to [" + cam_name_ + "]");
00149 
00150   return is_err;
00151 }
00152 
00153 
00154 INT UEyeCamDriver::disconnectCam() {
00155   INT is_err = IS_SUCCESS;
00156 
00157   if (isConnected()) {
00158     setStandbyMode();
00159 
00160     // Release existing camera buffers
00161     if (cam_buffer_ != NULL) {
00162       is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
00163     }
00164     cam_buffer_ = NULL;
00165 
00166     // Release camera handle
00167     is_err = is_ExitCamera(cam_handle_);
00168     cam_handle_ = (HIDS) 0;
00169 
00170     DEBUG_STREAM("Disconnected from [" + cam_name_ + "]");
00171   }
00172 
00173   return is_err;
00174 }
00175 
00176 
00177 INT UEyeCamDriver::loadCamConfig(string filename, bool ignore_load_failure) {
00178   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00179 
00180   INT is_err = IS_SUCCESS;
00181 
00182   // Convert filename to unicode, as requested by UEye API
00183   const wstring filenameU(filename.begin(), filename.end());
00184   if ((is_err = is_ParameterSet(cam_handle_, IS_PARAMETERSET_CMD_LOAD_FILE,
00185       (void*) filenameU.c_str(), 0)) != IS_SUCCESS) {
00186     WARN_STREAM("Could not load [" << cam_name_
00187       << "]'s sensor parameters file " << filename << " (" << err2str(is_err) << ")");
00188     if (ignore_load_failure) is_err = IS_SUCCESS;
00189     return is_err;
00190   } else {
00191     // After loading configuration settings, need to re-ensure that camera's
00192     // current configuration is supported by this driver wrapper
00193     // (note that this function also initializes the internal frame buffer)
00194     if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
00195 
00196     DEBUG_STREAM("Successfully loaded sensor parameter file for [" << cam_name_ <<
00197       "]: " << filename);
00198   }
00199 
00200   return is_err;
00201 }
00202 
00203 
00204 INT UEyeCamDriver::setColorMode(string& mode, bool reallocate_buffer) {
00205   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00206 
00207   INT is_err = IS_SUCCESS;
00208 
00209   // Stop capture to prevent access to memory buffer
00210   setStandbyMode();
00211 
00212   // Set to specified color mode
00213   color_mode_ = name2colormode(mode);
00214   if (!isSupportedColorMode(color_mode_)) {
00215     WARN_STREAM("Could not set color mode of [" << cam_name_
00216         << "] to " << mode << " (not supported by this wrapper). "
00217         << "switching to default mode: mono8");
00218     color_mode_ = IS_CM_MONO8;
00219     mode = "mono8";
00220   }
00221   if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
00222     ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
00223         "] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << " / '" << mode << "'). switching to default mode: mono8");
00224         
00225     color_mode_ = IS_CM_MONO8;
00226     mode = "mono8";
00227     if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
00228       ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
00229           "] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << "/ " << mode << ")");
00230       return is_err;
00231     }
00232   }
00233   bits_per_pixel_ = colormode2bpp(color_mode_);
00234 
00235   DEBUG_STREAM("Updated color mode to " << mode << "for [" << cam_name_ << "]");
00236 
00237   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00238 }
00239 
00240 
00241 INT UEyeCamDriver::setResolution(INT& image_width, INT& image_height,
00242     INT& image_left, INT& image_top, bool reallocate_buffer) {
00243   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00244 
00245   INT is_err = IS_SUCCESS;
00246 
00247   // Validate arguments
00248   CAP(image_width, 8, (INT) cam_sensor_info_.nMaxWidth);
00249   CAP(image_height, 4, (INT) cam_sensor_info_.nMaxHeight);
00250   if (image_left >= 0 && (int) cam_sensor_info_.nMaxWidth - image_width - image_left < 0) {
00251     WARN_STREAM("Cannot set AOI left index to " <<
00252         image_left << " with a frame width of " <<
00253         image_width << " and sensor max width of " <<
00254         cam_sensor_info_.nMaxWidth << " for [" << cam_name_ << "]");
00255     image_left = -1;
00256   }
00257   if (image_top >= 0 &&
00258       (int) cam_sensor_info_.nMaxHeight - image_height - image_top < 0) {
00259     WARN_STREAM("Cannot set AOI top index to " <<
00260         image_top << " with a frame height of " <<
00261         image_height << " and sensor max height of " <<
00262         cam_sensor_info_.nMaxHeight << " for [" << cam_name_ << "]");
00263     image_top = -1;
00264   }
00265   cam_aoi_.s32X = (image_left < 0) ?
00266       (cam_sensor_info_.nMaxWidth - image_width) / 2 : image_left;
00267   cam_aoi_.s32Y = (image_top < 0) ?
00268       (cam_sensor_info_.nMaxHeight - image_height) / 2 : image_top;
00269   cam_aoi_.s32Width = image_width;
00270   cam_aoi_.s32Height = image_height;
00271 
00272   const double s = cam_binning_rate_*cam_subsampling_rate_*cam_sensor_scaling_rate_;
00273   cam_aoi_.s32X /= s;
00274   cam_aoi_.s32Y /= s;
00275   cam_aoi_.s32Width /= s;
00276   cam_aoi_.s32Height /= s;
00277 
00278   if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_SET_AOI, &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
00279     ERROR_STREAM("Failed to set Area Of Interest (AOI) to " <<
00280       image_width << " x " << image_height <<
00281       " with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
00282       ") for [" << cam_name_ << "]" );
00283     return is_err;
00284   }
00285 
00286   DEBUG_STREAM("Updated Area Of Interest (AOI) to " <<
00287     image_width << " x " << image_height <<
00288     " with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
00289     ") for [" << cam_name_ << "]");
00290 
00291   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00292 }
00293 
00294 
00295 INT UEyeCamDriver::setSubsampling(int& rate, bool reallocate_buffer) {
00296   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00297 
00298   INT is_err = IS_SUCCESS;
00299 
00300   // Stop capture to prevent access to memory buffer
00301   setStandbyMode();
00302 
00303   INT rate_flag;
00304   INT supportedRates;
00305 
00306   supportedRates = is_SetSubSampling(cam_handle_, IS_GET_SUPPORTED_SUBSAMPLING);
00307   switch (rate) {
00308     case 1:
00309       rate_flag = IS_SUBSAMPLING_DISABLE;
00310       break;
00311     case 2:
00312       rate_flag = IS_SUBSAMPLING_2X;
00313       break;
00314     case 4:
00315       rate_flag = IS_SUBSAMPLING_4X;
00316       break;
00317     case 8:
00318       rate_flag = IS_SUBSAMPLING_8X;
00319       break;
00320     case 16:
00321       rate_flag = IS_SUBSAMPLING_16X;
00322       break;
00323     default:
00324       WARN_STREAM("[" << cam_name_ << "] currently has unsupported subsampling rate: " <<
00325         rate << ", resetting to 1X");
00326       rate = 1;
00327       rate_flag = IS_SUBSAMPLING_DISABLE;
00328       break;
00329   }
00330 
00331   if ((supportedRates & rate_flag) == rate_flag) {
00332     if ((is_err = is_SetSubSampling(cam_handle_, rate_flag)) != IS_SUCCESS) {
00333       ERROR_STREAM("Failed to set subsampling rate to " <<
00334         rate << "X for [" << cam_name_ << "] (" << err2str(is_err) << ")");
00335       return is_err;
00336     }
00337   } else {
00338     WARN_STREAM("[" << cam_name_ << "] does not support requested sampling rate of " << rate);
00339 
00340     // Query current rate
00341     INT currRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
00342     if (currRate == IS_SUBSAMPLING_DISABLE) { rate = 1; }
00343     else if (currRate == IS_SUBSAMPLING_2X) { rate = 2; }
00344     else if (currRate == IS_SUBSAMPLING_4X) { rate = 4; }
00345     else if (currRate == IS_SUBSAMPLING_8X) { rate = 8; }
00346     else if (currRate == IS_SUBSAMPLING_16X) { rate = 16; }
00347     else {
00348       WARN_STREAM("[" << cam_name_ << "] currently has an unsupported sampling rate (" <<
00349         currRate << "), resetting to 1X");
00350       if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
00351         ERROR_STREAM("Failed to set subsampling rate to 1X for [" << cam_name_ << "] (" <<
00352           err2str(is_err) << ")");
00353         return is_err;
00354       }
00355     }
00356     return IS_SUCCESS;
00357   }
00358 
00359   DEBUG_STREAM("Updated subsampling rate to " << rate << "X for [" << cam_name_ << "]");
00360 
00361   cam_subsampling_rate_ = rate;
00362 
00363   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00364 }
00365 
00366 
00367 INT UEyeCamDriver::setBinning(int& rate, bool reallocate_buffer) {
00368   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00369 
00370   INT is_err = IS_SUCCESS;
00371 
00372   // Stop capture to prevent access to memory buffer
00373   setStandbyMode();
00374 
00375   INT rate_flag;
00376   INT supportedRates;
00377 
00378   supportedRates = is_SetBinning(cam_handle_, IS_GET_SUPPORTED_BINNING);
00379   switch (rate) {
00380     case 1:
00381       rate_flag = IS_BINNING_DISABLE;
00382       break;
00383     case 2:
00384       rate_flag = IS_BINNING_2X;
00385       break;
00386     case 4:
00387       rate_flag = IS_BINNING_4X;
00388       break;
00389     case 8:
00390       rate_flag = IS_BINNING_8X;
00391       break;
00392     case 16:
00393       rate_flag = IS_BINNING_16X;
00394       break;
00395     default:
00396       WARN_STREAM("[" << cam_name_ << "] currently has unsupported binning rate: " <<
00397         rate << ", resetting to 1X");
00398       rate = 1;
00399       rate_flag = IS_BINNING_DISABLE;
00400       break;
00401   }
00402 
00403   if ((supportedRates & rate_flag) == rate_flag) {
00404     if ((is_err = is_SetBinning(cam_handle_, rate_flag)) != IS_SUCCESS) {
00405       ERROR_STREAM("Could not set binning rate for [" << cam_name_ << "] to " <<
00406         rate << "X (" << err2str(is_err) << ")");
00407       return is_err;
00408     }
00409   } else {
00410     WARN_STREAM("[" << cam_name_ << "] does not support requested binning rate of " << rate);
00411 
00412     // Query current rate
00413     INT currRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
00414     if (currRate == IS_BINNING_DISABLE) { rate = 1; }
00415     else if (currRate == IS_BINNING_2X) { rate = 2; }
00416     else if (currRate == IS_BINNING_4X) { rate = 4; }
00417     else if (currRate == IS_BINNING_8X) { rate = 8; }
00418     else if (currRate == IS_BINNING_16X) { rate = 16; }
00419     else {
00420       WARN_STREAM("[" << cam_name_ << "] currently has an unsupported binning rate (" <<
00421         currRate << "), resetting to 1X");
00422       if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
00423         ERROR_STREAM("Failed to set binning rate for [" << cam_name_ << "] to 1X (" <<
00424           err2str(is_err) << ")");
00425         return is_err;
00426       }
00427     }
00428     return IS_SUCCESS;
00429   }
00430 
00431   DEBUG_STREAM("Updated binning rate to " << rate << "X for [" << cam_name_ << "]");
00432 
00433   cam_binning_rate_ = rate;
00434 
00435   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00436 }
00437 
00438 
00439 INT UEyeCamDriver::setSensorScaling(double& rate, bool reallocate_buffer) {
00440   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00441 
00442   INT is_err = IS_SUCCESS;
00443 
00444   // Stop capture to prevent access to memory buffer
00445   setStandbyMode();
00446 
00447   SENSORSCALERINFO sensorScalerInfo;
00448   is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
00449   if (is_err == IS_NOT_SUPPORTED) {
00450     WARN_STREAM("[" << cam_name_ << "] does not support internal image scaling");
00451     rate = 1.0;
00452     cam_sensor_scaling_rate_ = 1.0;
00453     return IS_SUCCESS;
00454   } else if (is_err != IS_SUCCESS) {
00455     ERROR_STREAM("Failed to obtain supported internal image scaling information for [" <<
00456       cam_name_ << "] (" << err2str(is_err) << ")");
00457     rate = 1.0;
00458     cam_sensor_scaling_rate_ = 1.0;
00459     return is_err;
00460   } else {
00461     if (rate < sensorScalerInfo.dblMinFactor || rate > sensorScalerInfo.dblMaxFactor) {
00462       WARN_STREAM("Requested internal image scaling rate of " << rate <<
00463           " is not within supported bounds for [" << cam_name_ << "]: " <<
00464             sensorScalerInfo.dblMinFactor << ", " << sensorScalerInfo.dblMaxFactor <<
00465             "; not updating current rate of " << sensorScalerInfo.dblCurrFactor);
00466       rate = sensorScalerInfo.dblCurrFactor;
00467       return IS_SUCCESS;
00468     }
00469   }
00470 
00471   if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
00472     WARN_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
00473       "] to " << rate << "X (" << err2str(is_err) << "); resetting to 1X");
00474     rate = 1.0;
00475     if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
00476       ERROR_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
00477         "] to 1X (" << err2str(is_err) << ")");
00478       return is_err;
00479     }
00480   }
00481 
00482   DEBUG_STREAM("Updated internal image scaling rate to " << rate << "X for [" << cam_name_ << "]");
00483 
00484   cam_sensor_scaling_rate_ = rate;
00485 
00486   return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
00487 }
00488 
00489 
00490 INT UEyeCamDriver::setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
00491     INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost) {
00492   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00493 
00494   INT is_err = IS_SUCCESS;
00495 
00496   // Validate arguments
00497   CAP(master_gain_prc, 0, 100);
00498   CAP(red_gain_prc, 0, 100);
00499   CAP(green_gain_prc, 0, 100);
00500   CAP(blue_gain_prc, 0, 100);
00501 
00502   double pval1 = 0, pval2 = 0;
00503 
00504   if (auto_gain) {
00505     // Set auto gain
00506     pval1 = 1;
00507     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
00508         &pval1, &pval2)) != IS_SUCCESS) {
00509       if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
00510           &pval1, &pval2)) != IS_SUCCESS) {
00511         WARN_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
00512         auto_gain = false;
00513       }
00514     }
00515   } else {
00516     // Disable auto gain
00517     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
00518         &pval1, &pval2)) != IS_SUCCESS) {
00519       if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
00520           &pval1, &pval2)) != IS_SUCCESS) {
00521         DEBUG_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
00522       }
00523     }
00524 
00525     // Set gain boost
00526     if (is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
00527       gain_boost = false;
00528     } else {
00529       if ((is_err = is_SetGainBoost(cam_handle_,
00530           (gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF))
00531           != IS_SUCCESS) {
00532         WARN_STREAM("Failed to " << ((gain_boost) ? "enable" : "disable") <<
00533             " gain boost for [" << cam_name_ << "] (" << err2str(is_err) << ")");
00534       }
00535     }
00536 
00537     // Set manual gain parameters
00538     if ((is_err = is_SetHardwareGain(cam_handle_, master_gain_prc,
00539         red_gain_prc, green_gain_prc, blue_gain_prc)) != IS_SUCCESS) {
00540       WARN_STREAM("Failed to set manual gains (master: " << master_gain_prc <<
00541           "; red: " << red_gain_prc << "; green: " << green_gain_prc <<
00542           "; blue: " << blue_gain_prc << ") for [" << cam_name_ << "] (" <<
00543           err2str(is_err) << ")");
00544     }
00545   }
00546 
00547   if (auto_gain) {
00548     DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: auto");
00549   } else {
00550     DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: manual" <<
00551         "\n  master gain: " << master_gain_prc <<
00552         "\n  red gain: " << red_gain_prc <<
00553         "\n  green gain: " << green_gain_prc <<
00554         "\n  blue gain: " << blue_gain_prc <<
00555         "\n  gain boost: " << gain_boost);
00556   }
00557 
00558   return is_err;
00559 }
00560 
00561 
00562 INT UEyeCamDriver::setExposure(bool& auto_exposure, double& exposure_ms) {
00563   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00564 
00565   INT is_err = IS_SUCCESS;
00566 
00567   double minExposure, maxExposure;
00568 
00569   // Set auto exposure
00570   double pval1 = auto_exposure, pval2 = 0;
00571   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER,
00572       &pval1, &pval2)) != IS_SUCCESS) {
00573     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SHUTTER,
00574         &pval1, &pval2)) != IS_SUCCESS) {
00575       WARN_STREAM("Auto exposure mode is not supported for [" << cam_name_ <<
00576         "] (" << err2str(is_err) << ")");
00577       auto_exposure = false;
00578     }
00579   }
00580 
00581   // Set manual exposure timing
00582   if (!auto_exposure) {
00583     // Make sure that user-requested exposure rate is achievable
00584     if (((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN,
00585         (void*) &minExposure, sizeof(minExposure))) != IS_SUCCESS) ||
00586         ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX,
00587         (void*) &maxExposure, sizeof(maxExposure))) != IS_SUCCESS)) {
00588       ERROR_STREAM("Failed to query valid exposure range from [" << cam_name_ << "]");
00589       return is_err;
00590     }
00591     CAP(exposure_ms, minExposure, maxExposure);
00592 
00593     // Update exposure
00594     if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_SET_EXPOSURE,
00595         (void*) &(exposure_ms), sizeof(exposure_ms))) != IS_SUCCESS) {
00596       ERROR_STREAM("Failed to set exposure to " << exposure_ms <<
00597           " ms for [" << cam_name_ << "]");
00598       return is_err;
00599     }
00600   }
00601 
00602   DEBUG_STREAM("Updated exposure: " << ((auto_exposure) ? "auto" : to_string(exposure_ms)) <<
00603       " ms for [" << cam_name_ << "]");
00604 
00605   return is_err;
00606 }
00607 
00608 
00609 INT UEyeCamDriver::setWhiteBalance(bool& auto_white_balance, INT& red_offset,
00610     INT& blue_offset) {
00611   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00612 
00613   INT is_err = IS_SUCCESS;
00614 
00615   CAP(red_offset, -50, 50);
00616   CAP(blue_offset, -50, 50);
00617 
00618   // Set auto white balance mode and parameters
00619   double pval1 = auto_white_balance, pval2 = 0;
00620   // 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
00621   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_WHITEBALANCE,
00622       &pval1, &pval2)) != IS_SUCCESS) {
00623     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_ONCE,
00624         &pval1, &pval2)) != IS_SUCCESS) {
00625       WARN_STREAM("Auto white balance mode is not supported for [" << cam_name_ <<
00626         "] (" << err2str(is_err) << ")");
00627       auto_white_balance = false;
00628     }
00629   }
00630   if (auto_white_balance) {
00631     pval1 = red_offset;
00632     pval2 = blue_offset;
00633     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_OFFSET,
00634         &pval1, &pval2)) != IS_SUCCESS) {
00635       WARN_STREAM("Failed to set white balance red/blue offsets to " <<
00636           red_offset << " / " << blue_offset <<
00637           " for [" << cam_name_ << "] (" << err2str(is_err) << ")");
00638     }
00639   }
00640 
00641   DEBUG_STREAM("Updated white balance for [" << cam_name_ << "]: " <<
00642     ((auto_white_balance) ? "auto" : "manual") <<
00643     "\n  red offset: " << red_offset <<
00644     "\n  blue offset: " << blue_offset);
00645 
00646   return is_err;
00647 }
00648 
00649 
00650 INT UEyeCamDriver::setFrameRate(bool& auto_frame_rate, double& frame_rate_hz) {
00651   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00652 
00653   INT is_err = IS_SUCCESS;
00654 
00655   double pval1 = 0, pval2 = 0;
00656   double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
00657 
00658   // Make sure that auto shutter is enabled before enabling auto frame rate
00659   bool autoShutterOn = false;
00660   is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
00661   autoShutterOn |= (pval1 != 0);
00662   is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
00663   autoShutterOn |= (pval1 != 0);
00664   if (!autoShutterOn) {
00665     auto_frame_rate = false;
00666   }
00667 
00668   // Set frame rate / auto
00669   pval1 = auto_frame_rate;
00670   if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE,
00671       &pval1, &pval2)) != IS_SUCCESS) {
00672     if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_FRAMERATE,
00673         &pval1, &pval2)) != IS_SUCCESS) {
00674       WARN_STREAM("Auto frame rate mode is not supported for [" << cam_name_ <<
00675         "] (" << err2str(is_err) << ")");
00676       auto_frame_rate = false;
00677     }
00678   }
00679   if (!auto_frame_rate) {
00680     // Make sure that user-requested frame rate is achievable
00681     if ((is_err = is_GetFrameTimeRange(cam_handle_, &minFrameTime,
00682         &maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
00683       ERROR_STREAM("Failed to query valid frame rate range from [" << cam_name_ <<
00684         "] (" << err2str(is_err) << ")");
00685       return is_err;
00686     }
00687     CAP(frame_rate_hz, 1.0/maxFrameTime, 1.0/minFrameTime);
00688 
00689     // Update frame rate
00690     if ((is_err = is_SetFrameRate(cam_handle_, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
00691       ERROR_STREAM("Failed to set frame rate to " << frame_rate_hz <<
00692           " MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
00693       return is_err;
00694     } else if (frame_rate_hz != newFrameRate) {
00695       frame_rate_hz = newFrameRate;
00696     }
00697   }
00698 
00699   DEBUG_STREAM("Updated frame rate for [" << cam_name_ << "]: " <<
00700     ((auto_frame_rate) ? "auto" : to_string(frame_rate_hz)) << " Hz");
00701 
00702   return is_err;
00703 }
00704 
00705 
00706 INT UEyeCamDriver::setPixelClockRate(INT& clock_rate_mhz) {
00707   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00708 
00709   INT is_err = IS_SUCCESS;
00710 
00711   UINT pixelClockList[150];  // No camera has more than 150 different pixel clocks (uEye manual)
00712   UINT numberOfSupportedPixelClocks = 0;
00713   if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_NUMBER,
00714       (void*) &numberOfSupportedPixelClocks, sizeof(numberOfSupportedPixelClocks))) != IS_SUCCESS) {
00715     ERROR_STREAM("Failed to query number of supported pixel clocks from [" << cam_name_ <<
00716       "] (" << err2str(is_err) << ")");
00717     return is_err;
00718   }
00719   if(numberOfSupportedPixelClocks > 0) {
00720     ZeroMemory(pixelClockList, sizeof(pixelClockList));
00721     if((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_LIST,
00722        (void*) pixelClockList, numberOfSupportedPixelClocks * sizeof(int))) != IS_SUCCESS) {
00723       ERROR_STREAM("Failed to query list of supported pixel clocks from [" << cam_name_ <<
00724         "] (" << err2str(is_err) << ")");
00725       return is_err;
00726     }
00727   }
00728   int minPixelClock = (int) pixelClockList[0];
00729   int maxPixelClock = (int) pixelClockList[numberOfSupportedPixelClocks-1];
00730   CAP(clock_rate_mhz, minPixelClock, maxPixelClock);
00731 
00732   // As list is sorted smallest to largest...
00733   for(UINT i = 0; i < numberOfSupportedPixelClocks; i++) {
00734     if(clock_rate_mhz <= (int) pixelClockList[i]) {
00735       clock_rate_mhz = pixelClockList[i];  // ...get the closest-larger-or-equal from the list
00736       break;
00737     }
00738   }
00739 
00740   if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_SET,
00741       (void*) &(clock_rate_mhz), sizeof(clock_rate_mhz))) != IS_SUCCESS) {
00742     ERROR_STREAM("Failed to set pixel clock to " << clock_rate_mhz <<
00743         "MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
00744     return is_err;
00745   }
00746 
00747   DEBUG_STREAM("Updated pixel clock for [" << cam_name_ << "]: " << clock_rate_mhz << " MHz");
00748 
00749   return IS_SUCCESS;
00750 }
00751 
00752 
00753 INT UEyeCamDriver::setFlashParams(INT& delay_us, UINT& duration_us) {
00754   INT is_err = IS_SUCCESS;
00755 
00756   // Make sure parameters are within range supported by camera
00757   IO_FLASH_PARAMS minFlashParams, maxFlashParams, newFlashParams;
00758   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MIN,
00759       (void*) &minFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00760     ERROR_STREAM("Could not retrieve flash parameter info (min) for [" << cam_name_ <<
00761       "] (" << err2str(is_err) << ")");
00762     return is_err;
00763   }
00764   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MAX,
00765       (void*) &maxFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00766     ERROR_STREAM("Could not retrieve flash parameter info (max) for [" << cam_name_ <<
00767       "] (" << err2str(is_err) << ")");
00768     return is_err;
00769   }
00770   delay_us = (delay_us < minFlashParams.s32Delay) ? minFlashParams.s32Delay :
00771       ((delay_us > maxFlashParams.s32Delay) ? maxFlashParams.s32Delay : delay_us);
00772   duration_us = (duration_us < minFlashParams.u32Duration && duration_us != 0) ? minFlashParams.u32Duration :
00773       ((duration_us > maxFlashParams.u32Duration) ? maxFlashParams.u32Duration : duration_us);
00774   newFlashParams.s32Delay = delay_us;
00775   newFlashParams.u32Duration = duration_us;
00776   // WARNING: Setting s32Duration to 0, according to documentation, means
00777   //          setting duration to total exposure time. If non-ext-triggered
00778   //          camera is operating at fastest grab rate, then the resulting
00779   //          flash signal will APPEAR as active LO when set to active HIGH,
00780   //          and vice versa. This is why the duration is set manually.
00781   if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_PARAMS,
00782       (void*) &newFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00783     ERROR_STREAM("Could not set flash parameter info for [" << cam_name_ <<
00784       "] (" << err2str(is_err) << ")");
00785     return is_err;
00786   }
00787 
00788   return is_err;
00789 }
00790 
00791 
00792 INT UEyeCamDriver::setFreeRunMode() {
00793   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00794 
00795   INT is_err = IS_SUCCESS;
00796 
00797   if (!freeRunModeActive()) {
00798     setStandbyMode(); // No need to check for success
00799 
00800     // Set the flash to a high active pulse for each image in the trigger mode
00801     INT flash_delay = 0;
00802     UINT flash_duration = 1000;
00803     setFlashParams(flash_delay, flash_duration);
00804     UINT nMode = IO_FLASH_MODE_FREERUN_HI_ACTIVE;
00805     if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
00806         (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
00807       WARN_STREAM("Could not set free-run active-low flash output for [" << cam_name_ <<
00808         "] (" << err2str(is_err) << ")");
00809       WARN_STREAM("WARNING: camera hardware does not support ueye_cam's master-slave synchronization method");
00810     }
00811 
00812     if ((is_err = is_EnableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00813       ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
00814         "] (" << err2str(is_err) << ")");
00815       return is_err;
00816     }
00817     if ((is_err = is_CaptureVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00818       ERROR_STREAM("Could not start free-run live video mode for [" << cam_name_ <<
00819         "] (" << err2str(is_err) << ")");
00820       return is_err;
00821     }
00822     DEBUG_STREAM("Started live video mode for [" << cam_name_ << "]");
00823   }
00824 
00825   return is_err;
00826 }
00827 
00828 
00829 INT UEyeCamDriver::setExtTriggerMode() {
00830   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00831 
00832   INT is_err = IS_SUCCESS;
00833 
00834   if (!extTriggerModeActive()) {
00835     setStandbyMode(); // No need to check for success
00836 
00837     if ((is_err = is_EnableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00838       ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
00839         "] (" << err2str(is_err) << ")");
00840       return is_err;
00841     }
00842 
00843     if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_HI_LO)) != IS_SUCCESS) {
00844       ERROR_STREAM("Could not enable falling-edge external trigger mode for [" <<
00845         cam_name_ << "] (" << err2str(is_err) << ")");
00846       return is_err;
00847     }
00848     if ((is_err = is_CaptureVideo(cam_handle_, IS_DONT_WAIT)) != IS_SUCCESS) {
00849       ERROR_STREAM("Could not start external trigger live video mode for [" <<
00850         cam_name_ << "] (" << err2str(is_err) << ")");
00851       return is_err;
00852     }
00853     DEBUG_STREAM("Started falling-edge external trigger live video mode for [" <<
00854       cam_name_ << "]");
00855   }
00856 
00857   return is_err;
00858 }
00859 
00860 
00861 INT UEyeCamDriver::setMirrorUpsideDown(bool flip_horizontal){
00862   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00863 
00864   INT is_err = IS_SUCCESS;
00865   if(flip_horizontal)
00866      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,1,0);
00867   else
00868      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,0,0);
00869 
00870   return is_err;
00871 }
00872 
00873 
00874 INT UEyeCamDriver::setMirrorLeftRight(bool flip_vertical){
00875   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00876 
00877   INT is_err = IS_SUCCESS;
00878   if(flip_vertical)
00879      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,1,0);
00880   else
00881      is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,0,0);
00882 
00883   return is_err;
00884 }
00885 
00886 
00887 INT UEyeCamDriver::setStandbyMode() {
00888   if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
00889 
00890   INT is_err = IS_SUCCESS;
00891 
00892   if (extTriggerModeActive()) {
00893       if ((is_err = is_DisableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00894         ERROR_STREAM("Could not disable frame event for [" << cam_name_ <<
00895           "] (" << err2str(is_err) << ")");
00896         return is_err;
00897       }
00898       if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_OFF)) != IS_SUCCESS) {
00899         ERROR_STREAM("Could not disable external trigger mode for [" << cam_name_ <<
00900           "] (" << err2str(is_err) << ")");
00901         return is_err;
00902       }
00903       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)
00904       if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00905         ERROR_STREAM("Could not stop live video mode for [" << cam_name_ <<
00906           "] (" << err2str(is_err) << ")");
00907         return is_err;
00908       }
00909       DEBUG_STREAM("Stopped external trigger mode for [" << cam_name_ << "]");
00910   } else if (freeRunModeActive()) {
00911     UINT nMode = IO_FLASH_MODE_OFF;
00912     if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
00913         (void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
00914       ERROR_STREAM("Could not disable flash output for [" << cam_name_ <<
00915         "] (" << err2str(is_err) << ")");
00916       return is_err;
00917     }
00918     if ((is_err = is_DisableEvent(cam_handle_, IS_SET_EVENT_FRAME)) != IS_SUCCESS) {
00919       ERROR_STREAM("Could not disable frame event for [" << cam_name_ <<
00920         "] (" << err2str(is_err) << ")");
00921       return is_err;
00922     }
00923     if ((is_err = is_StopLiveVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
00924       ERROR_STREAM("Could not stop live video mode for [" << cam_name_ <<
00925         "] (" << err2str(is_err) << ")");
00926       return is_err;
00927     }
00928     DEBUG_STREAM("Stopped free-run live video mode for [" << cam_name_ << "]");
00929   }
00930   if ((is_err = is_CameraStatus(cam_handle_, IS_STANDBY, IS_GET_STATUS)) != IS_SUCCESS) {
00931     ERROR_STREAM("Could not set standby mode for [" << cam_name_ <<
00932       "] (" << err2str(is_err) << ")");
00933     return is_err;
00934   }
00935 
00936   return is_err;
00937 }
00938 
00939 
00940 const char* UEyeCamDriver::processNextFrame(INT timeout_ms) {
00941   if (!freeRunModeActive() && !extTriggerModeActive()) return NULL;
00942 
00943   INT is_err = IS_SUCCESS;
00944 
00945   // Wait for frame event
00946   if ((is_err = is_WaitEvent(cam_handle_, IS_SET_EVENT_FRAME,
00947         timeout_ms)) != IS_SUCCESS) {
00948     if (is_err == IS_TIMED_OUT) {
00949       ERROR_STREAM("Timed out while acquiring image from [" << cam_name_ <<
00950         "] (" << err2str(is_err) << ")");
00951       ERROR_STREAM("If this is occurring frequently, see https://github.com/anqixu/ueye_cam/issues/6#issuecomment-49925549");
00952       handleTimeout();
00953     } else {
00954       ERROR_STREAM("Failed to acquire image from [" << cam_name_ <<
00955         "] (" << err2str(is_err) << ")");
00956     }
00957     return NULL;
00958   }
00959 
00960   return cam_buffer_;
00961 }
00962 
00963 
00964 INT UEyeCamDriver::syncCamConfig(string dft_mode_str) {
00965   INT is_err = IS_SUCCESS;
00966 
00967   // Synchronize resolution, color mode, bits per pixel settings
00968   if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_GET_AOI,
00969       (void*) &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
00970     ERROR_STREAM("Could not retrieve Area Of Interest (AOI) information from [" <<
00971       cam_name_ << "] (" << err2str(is_err) << ")");
00972     return is_err;
00973   }
00974   color_mode_ = is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE);
00975   if (!isSupportedColorMode(color_mode_)) {
00976     WARN_STREAM("Current color mode (IDS format: " << colormode2str(color_mode_)
00977         << ") for [" << cam_name_ << "] is not supported by this wrapper; "
00978         //<< "supported modes: {mono8 | mono10 | mono12 | mono16 | bayer_rggb8 | rgb8 | bgr8 | rgb10 | bgr10 | rgb10u | bgr10u | rgb12u | bgr12u}; "
00979         << "switching to default mode: " << dft_mode_str);
00980     if ((is_err = setColorMode(dft_mode_str, false)) != IS_SUCCESS) return is_err;
00981     // reallocate_buffer == false, since this fn will force-re-allocate anyways
00982   }
00983   bits_per_pixel_ = colormode2bpp(color_mode_);
00984 
00985   // Synchronize sensor scaling rate setting
00986   SENSORSCALERINFO sensorScalerInfo;
00987   is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
00988   if (is_err == IS_NOT_SUPPORTED) {
00989     cam_sensor_scaling_rate_ = 1.0;
00990   } else if (is_err != IS_SUCCESS) {
00991     ERROR_STREAM("Could not obtain supported internal image scaling information for [" <<
00992       cam_name_ << "] (" << err2str(is_err) << ")");
00993     return is_err;
00994   } else {
00995     cam_sensor_scaling_rate_ = sensorScalerInfo.dblCurrFactor;
00996   }
00997 
00998   // Synchronize subsampling rate setting
00999   const INT currSubsamplingRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
01000   switch (currSubsamplingRate) {
01001     case (IS_SUBSAMPLING_DISABLE): cam_subsampling_rate_ = 1; break;
01002     case (IS_SUBSAMPLING_2X): cam_subsampling_rate_ = 2; break;
01003     case (IS_SUBSAMPLING_4X): cam_subsampling_rate_ = 4; break;
01004     case (IS_SUBSAMPLING_8X): cam_subsampling_rate_ = 8; break;
01005     case (IS_SUBSAMPLING_16X): cam_subsampling_rate_ = 16; break;
01006     default:
01007       WARN_STREAM("Current sampling rate (IDS setting: " << currSubsamplingRate
01008           << ") for [" << cam_name_ << "] is not supported by this wrapper; resetting to 1X");
01009       if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
01010         ERROR_STREAM("Could not set subsampling rate for [" << cam_name_
01011             << "] to 1X (" << err2str(is_err) << ")");
01012         return is_err;
01013       }
01014       cam_subsampling_rate_ = 1; break;
01015   }
01016 
01017   // Synchronize binning rate setting
01018   const INT currBinningRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
01019   switch (currBinningRate) {
01020     case (IS_BINNING_DISABLE): cam_binning_rate_ = 1; break;
01021     case (IS_BINNING_2X): cam_binning_rate_ = 2; break;
01022     case (IS_BINNING_4X): cam_binning_rate_ = 4; break;
01023     case (IS_BINNING_8X): cam_binning_rate_ = 8; break;
01024     case (IS_BINNING_16X): cam_binning_rate_ = 16; break;
01025     default:
01026       WARN_STREAM("Current binning rate (IDS setting: " << currBinningRate
01027           << ") for [" << cam_name_ << "] is not supported by this wrapper; resetting to 1X");
01028       if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
01029         ERROR_STREAM("Could not set binning rate for [" << cam_name_
01030             << "] to 1X (" << err2str(is_err) << ")");
01031         return is_err;
01032       }
01033       cam_binning_rate_ = 1; break;
01034   }
01035 
01036   // Report synchronized settings
01037   DEBUG_STREAM("Synchronized configuration of [" << cam_name_ <<
01038     "] and ensured compatibility with driver wrapper:" <<
01039     "\n  AOI width: " << cam_aoi_.s32Width <<
01040     "\n  AOI height: " << cam_aoi_.s32Height <<
01041     "\n  AOI top-left X: " << cam_aoi_.s32X <<
01042     "\n  AOI top-left Y: " << cam_aoi_.s32Y <<
01043     "\n  IDS color mode: " << colormode2str(color_mode_) <<
01044     "\n  bits per pixel: " << bits_per_pixel_ <<
01045     "\n  sensor scaling rate: " << cam_sensor_scaling_rate_ <<
01046     "\n  subsampling rate: " << cam_subsampling_rate_ <<
01047     "\n  binning rate: " << cam_binning_rate_);
01048 
01049   // Force (re-)allocate internal frame buffer
01050   return reallocateCamBuffer();
01051 }
01052 
01053 
01054 INT UEyeCamDriver::reallocateCamBuffer() {
01055   INT is_err = IS_SUCCESS;
01056 
01057   // Stop capture to prevent access to memory buffer
01058   setStandbyMode();
01059 
01060   // Free existing memory from previous calls to reallocateCamBuffer()
01061   if (cam_buffer_ != NULL) {
01062     is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
01063     cam_buffer_ = NULL;
01064   }
01065 
01066   // Query camera's current resolution settings, for redundancy
01067   if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_GET_AOI,
01068       (void*) &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
01069     ERROR_STREAM("Could not retrieve Area Of Interest (AOI) information for [" <<
01070       cam_name_ << "] (" << err2str(is_err) << ")");
01071     return is_err;
01072   }
01073 
01074   // Allocate new memory section for IDS driver to use as frame buffer
01075   if ((is_err = is_AllocImageMem(cam_handle_, cam_aoi_.s32Width, cam_aoi_.s32Height,
01076       bits_per_pixel_, &cam_buffer_, &cam_buffer_id_)) != IS_SUCCESS) {
01077     ERROR_STREAM("Failed to allocate " << cam_aoi_.s32Width << " x " << cam_aoi_.s32Height <<
01078       " image buffer for [" << cam_name_ << "]");
01079     return is_err;
01080   }
01081 
01082   // Tell IDS driver to use allocated memory section as frame buffer
01083   if ((is_err = is_SetImageMem(cam_handle_, cam_buffer_, cam_buffer_id_)) != IS_SUCCESS) {
01084     ERROR_STREAM("Failed to associate image buffer to IDS driver for [" <<
01085       cam_name_ << "] (" << err2str(is_err) << ")");
01086     return is_err;
01087   }
01088 
01089   // Synchronize internal settings for buffer step size and overall buffer size
01090   // NOTE: assume that sensor_scaling_rate, subsampling_rate, and cam_binning_rate_
01091   //       have all been previously validated and synchronized by syncCamConfig()
01092   if ((is_err = is_GetImageMemPitch(cam_handle_, &cam_buffer_pitch_)) != IS_SUCCESS) {
01093     ERROR_STREAM("Failed to query buffer step size / pitch / stride for [" <<
01094       cam_name_ << "] (" << err2str(is_err) << ")");
01095     return is_err;
01096   }
01097   if (cam_buffer_pitch_ < cam_aoi_.s32Width * bits_per_pixel_/8) {
01098     ERROR_STREAM("Frame buffer's queried step size (" << cam_buffer_pitch_ <<
01099       ") is smaller than buffer's expected stride [= width (" << cam_aoi_.s32Width << ") * bits per pixel (" << bits_per_pixel_ << ") /8] for [" << cam_name_ <<
01100       "]\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
01101   }
01102   cam_buffer_size_ = cam_buffer_pitch_ * cam_aoi_.s32Height;
01103 
01104   // Report updated settings
01105   DEBUG_STREAM("Allocated internal memory for [" << cam_name_ << "]:" <<
01106     "\n  buffer width: " << cam_aoi_.s32Width <<
01107     "\n  buffer height: " << cam_aoi_.s32Height <<
01108     "\n  buffer step/pitch/stride: " << cam_buffer_pitch_ <<
01109     "\n  expected bits per pixel: " << bits_per_pixel_ <<
01110     "\n  expected buffer size: " << cam_buffer_size_);
01111 
01112   return is_err;
01113 }
01114 
01115 
01116 const char* UEyeCamDriver::err2str(INT error) {
01117 #define CASE(s) case s: return #s; break
01118   switch (error) {
01119   CASE(IS_NO_SUCCESS);
01120   CASE(IS_SUCCESS);
01121   CASE(IS_INVALID_CAMERA_HANDLE);
01122   CASE(IS_IO_REQUEST_FAILED);
01123   CASE(IS_CANT_OPEN_DEVICE);
01124   CASE(IS_CANT_OPEN_REGISTRY);
01125   CASE(IS_CANT_READ_REGISTRY);
01126   CASE(IS_NO_IMAGE_MEM_ALLOCATED);
01127   CASE(IS_CANT_CLEANUP_MEMORY);
01128   CASE(IS_CANT_COMMUNICATE_WITH_DRIVER);
01129   CASE(IS_FUNCTION_NOT_SUPPORTED_YET);
01130   CASE(IS_INVALID_CAPTURE_MODE);
01131   CASE(IS_INVALID_MEMORY_POINTER);
01132   CASE(IS_FILE_WRITE_OPEN_ERROR);
01133   CASE(IS_FILE_READ_OPEN_ERROR);
01134   CASE(IS_FILE_READ_INVALID_BMP_ID);
01135   CASE(IS_FILE_READ_INVALID_BMP_SIZE);
01136   CASE(IS_NO_ACTIVE_IMG_MEM);
01137   CASE(IS_SEQUENCE_LIST_EMPTY);
01138   CASE(IS_CANT_ADD_TO_SEQUENCE);
01139   CASE(IS_SEQUENCE_BUF_ALREADY_LOCKED);
01140   CASE(IS_INVALID_DEVICE_ID);
01141   CASE(IS_INVALID_BOARD_ID);
01142   CASE(IS_ALL_DEVICES_BUSY);
01143   CASE(IS_TIMED_OUT);
01144   CASE(IS_NULL_POINTER);
01145   CASE(IS_INVALID_PARAMETER);
01146   CASE(IS_OUT_OF_MEMORY);
01147   CASE(IS_ACCESS_VIOLATION);
01148   CASE(IS_NO_USB20);
01149   CASE(IS_CAPTURE_RUNNING);
01150   CASE(IS_IMAGE_NOT_PRESENT);
01151   CASE(IS_TRIGGER_ACTIVATED);
01152   CASE(IS_CRC_ERROR);
01153   CASE(IS_NOT_YET_RELEASED);
01154   CASE(IS_WAITING_FOR_KERNEL);
01155   CASE(IS_NOT_SUPPORTED);
01156   CASE(IS_TRIGGER_NOT_ACTIVATED);
01157   CASE(IS_OPERATION_ABORTED);
01158   CASE(IS_BAD_STRUCTURE_SIZE);
01159   CASE(IS_INVALID_BUFFER_SIZE);
01160   CASE(IS_INVALID_PIXEL_CLOCK);
01161   CASE(IS_INVALID_EXPOSURE_TIME);
01162   CASE(IS_AUTO_EXPOSURE_RUNNING);
01163   CASE(IS_CANNOT_CREATE_BB_SURF);
01164   CASE(IS_CANNOT_CREATE_BB_MIX);
01165   CASE(IS_BB_OVLMEM_NULL);
01166   CASE(IS_CANNOT_CREATE_BB_OVL);
01167   CASE(IS_NOT_SUPP_IN_OVL_SURF_MODE);
01168   CASE(IS_INVALID_SURFACE);
01169   CASE(IS_SURFACE_LOST);
01170   CASE(IS_RELEASE_BB_OVL_DC);
01171   CASE(IS_BB_TIMER_NOT_CREATED);
01172   CASE(IS_BB_OVL_NOT_EN);
01173   CASE(IS_ONLY_IN_BB_MODE);
01174   CASE(IS_INVALID_COLOR_FORMAT);
01175   CASE(IS_INVALID_WB_BINNING_MODE);
01176   CASE(IS_INVALID_I2C_DEVICE_ADDRESS);
01177   CASE(IS_COULD_NOT_CONVERT);
01178   CASE(IS_TRANSFER_ERROR);
01179   CASE(IS_PARAMETER_SET_NOT_PRESENT);
01180   CASE(IS_INVALID_CAMERA_TYPE);
01181   CASE(IS_INVALID_HOST_IP_HIBYTE);
01182   CASE(IS_CM_NOT_SUPP_IN_CURR_DISPLAYMODE);
01183   CASE(IS_NO_IR_FILTER);
01184   CASE(IS_STARTER_FW_UPLOAD_NEEDED);
01185   CASE(IS_DR_LIBRARY_NOT_FOUND);
01186   CASE(IS_DR_DEVICE_OUT_OF_MEMORY);
01187   CASE(IS_DR_CANNOT_CREATE_SURFACE);
01188   CASE(IS_DR_CANNOT_CREATE_VERTEX_BUFFER);
01189   CASE(IS_DR_CANNOT_CREATE_TEXTURE);
01190   CASE(IS_DR_CANNOT_LOCK_OVERLAY_SURFACE);
01191   CASE(IS_DR_CANNOT_UNLOCK_OVERLAY_SURFACE);
01192   CASE(IS_DR_CANNOT_GET_OVERLAY_DC);
01193   CASE(IS_DR_CANNOT_RELEASE_OVERLAY_DC);
01194   CASE(IS_DR_DEVICE_CAPS_INSUFFICIENT);
01195   CASE(IS_INCOMPATIBLE_SETTING);
01196   CASE(IS_DR_NOT_ALLOWED_WHILE_DC_IS_ACTIVE);
01197   CASE(IS_DEVICE_ALREADY_PAIRED);
01198   CASE(IS_SUBNETMASK_MISMATCH);
01199   CASE(IS_SUBNET_MISMATCH);
01200   CASE(IS_INVALID_IP_CONFIGURATION);
01201   CASE(IS_DEVICE_NOT_COMPATIBLE);
01202   CASE(IS_NETWORK_FRAME_SIZE_INCOMPATIBLE);
01203   CASE(IS_NETWORK_CONFIGURATION_INVALID);
01204   CASE(IS_ERROR_CPU_IDLE_STATES_CONFIGURATION);
01205   default:
01206     return "UNKNOWN ERROR";
01207     break;
01208   }
01209   return "UNKNOWN ERROR";
01210 #undef CASE
01211 }
01212 
01213 
01214 const char* UEyeCamDriver::colormode2str(INT mode) {
01215 #define CASE(s) case s: return #s; break
01216   switch (mode) {
01217   CASE(IS_CM_MONO16);
01218   CASE(IS_CM_MONO12);
01219   CASE(IS_CM_MONO10);
01220   CASE(IS_CM_MONO8);
01221   CASE(IS_CM_SENSOR_RAW16);
01222   CASE(IS_CM_SENSOR_RAW12);
01223   CASE(IS_CM_SENSOR_RAW10);
01224   CASE(IS_CM_SENSOR_RAW8);
01225   CASE(IS_CM_RGB12_UNPACKED);
01226   CASE(IS_CM_RGB10_UNPACKED);
01227   CASE(IS_CM_RGB10_PACKED);
01228   CASE(IS_CM_RGB8_PACKED);
01229   CASE(IS_CM_RGBA12_UNPACKED);
01230   CASE(IS_CM_RGBA8_PACKED);
01231   CASE(IS_CM_RGBY8_PACKED);
01232   CASE(IS_CM_BGR12_UNPACKED);
01233   CASE(IS_CM_BGR10_UNPACKED);
01234   CASE(IS_CM_BGR10_PACKED);
01235   CASE(IS_CM_BGR8_PACKED);
01236   CASE(IS_CM_BGRA12_UNPACKED);
01237   CASE(IS_CM_BGRA8_PACKED);
01238   CASE(IS_CM_BGRY8_PACKED);
01239   CASE(IS_CM_RGB8_PLANAR);
01240   CASE(IS_CM_BGR565_PACKED);
01241   CASE(IS_CM_BGR5_PACKED);
01242   CASE(IS_CM_UYVY_PACKED);
01243   CASE(IS_CM_CBYCRY_PACKED);
01244   CASE(IS_CM_PREFER_PACKED_SOURCE_FORMAT);
01245   CASE(IS_CM_JPEG);
01246   // The following are obsolete formats according to
01247   // https://en.ids-imaging.com/manuals/uEye_SDK/EN/uEye_Manual/index.html
01248   // CASE(IS_SET_CM_RGB32);
01249   // CASE(IS_SET_CM_RGB24);
01250   // CASE(IS_SET_CM_RGB16);
01251   // CASE(IS_SET_CM_RGB15);
01252   // CASE(IS_SET_CM_Y8);
01253   // CASE(IS_SET_CM_BAYER);
01254   // CASE(IS_SET_CM_UYVY);
01255   // CASE(IS_SET_CM_UYVY_MONO);
01256   // CASE(IS_SET_CM_UYVY_BAYER);
01257   // CASE(IS_SET_CM_CBYCRY);
01258   // CASE(IS_SET_CM_RGBY);
01259   // CASE(IS_SET_CM_RGB30);
01260   // CASE(IS_SET_CM_Y12);
01261   // CASE(IS_SET_CM_BAYER12);
01262   // CASE(IS_SET_CM_Y16);
01263   // CASE(IS_SET_CM_BAYER16);
01264   // CASE(IS_CM_BGR10V2_PACKED);
01265   // CASE(IS_CM_RGB10V2_PACKED);
01266   // CASE(IS_CM_BGR555_PACKED);
01267   // CASE(IS_CM_BAYER_RG8);
01268   // CASE(IS_CM_BAYER_RG12);
01269   // CASE(IS_CM_BAYER_RG16);
01270   // CASE(IS_CM_RGB12_PACKED);
01271   // CASE(IS_CM_RGBA12_PACKED);
01272   // CASE(IS_CM_BGR12_PACKED);
01273   // CASE(IS_CM_BGRA12_PACKED);
01274   default:
01275     return "UNKNOWN COLOR MODE";
01276     break;
01277   }
01278   return "UNKNOWN COLOR MODE";
01279 #undef CASE
01280 }
01281 
01282 
01283 const INT UEyeCamDriver::colormode2bpp(INT mode) {
01284   switch (mode) {
01285     case IS_CM_SENSOR_RAW8:
01286     case IS_CM_MONO8:
01287       return 8;
01288     case IS_CM_SENSOR_RAW10:
01289     case IS_CM_SENSOR_RAW12:
01290     case IS_CM_SENSOR_RAW16:
01291     case IS_CM_MONO10:
01292     case IS_CM_MONO12:
01293     case IS_CM_MONO16:
01294     case IS_CM_BGR5_PACKED:
01295     case IS_CM_BGR565_PACKED:
01296     case IS_CM_UYVY_PACKED:
01297     case IS_CM_UYVY_MONO_PACKED:
01298     case IS_CM_UYVY_BAYER_PACKED:
01299     case IS_CM_CBYCRY_PACKED:
01300       return 16;
01301     case IS_CM_RGB8_PACKED:
01302     case IS_CM_BGR8_PACKED:
01303     case IS_CM_RGB8_PLANAR:
01304       return 24;
01305     case IS_CM_RGBA8_PACKED:
01306     case IS_CM_BGRA8_PACKED:
01307     case IS_CM_RGBY8_PACKED:
01308     case IS_CM_BGRY8_PACKED:
01309     case IS_CM_RGB10_PACKED:
01310     case IS_CM_BGR10_PACKED:
01311       return 32;
01312     case IS_CM_RGB10_UNPACKED:
01313     case IS_CM_BGR10_UNPACKED:
01314     case IS_CM_RGB12_UNPACKED:
01315     case IS_CM_BGR12_UNPACKED:
01316       return 48;
01317     case IS_CM_RGBA12_UNPACKED:
01318     case IS_CM_BGRA12_UNPACKED:
01319       return 64;
01320 //   case IS_CM_JPEG:
01321     default:
01322       return 0;
01323   }
01324 }
01325 
01326 
01327 const bool UEyeCamDriver::isSupportedColorMode(INT mode) {
01328   switch (mode) {
01329     case IS_CM_SENSOR_RAW8:
01330     case IS_CM_SENSOR_RAW10:
01331     case IS_CM_SENSOR_RAW12:
01332     case IS_CM_SENSOR_RAW16:
01333     case IS_CM_MONO8:
01334     case IS_CM_MONO10:
01335     case IS_CM_MONO12:
01336     case IS_CM_MONO16:
01337     case IS_CM_RGB8_PACKED:
01338     case IS_CM_BGR8_PACKED:
01339     case IS_CM_RGB8_PLANAR:
01340     case IS_CM_RGB10_PACKED:
01341     case IS_CM_BGR10_PACKED:
01342     case IS_CM_RGB10_UNPACKED:
01343     case IS_CM_BGR10_UNPACKED:
01344     case IS_CM_RGB12_UNPACKED:
01345     case IS_CM_BGR12_UNPACKED:
01346       return true;
01347 //    case IS_CM_BGR5_PACKED:
01348 //    case IS_CM_BGR565_PACKED:
01349 //    case IS_CM_UYVY_PACKED:
01350 //    case IS_CM_UYVY_MONO_PACKED:
01351 //    case IS_CM_UYVY_BAYER_PACKED:
01352 //    case IS_CM_CBYCRY_PACKED:
01353 //    case IS_CM_RGBA8_PACKED:
01354 //    case IS_CM_BGRA8_PACKED:
01355 //    case IS_CM_RGBY8_PACKED:
01356 //    case IS_CM_BGRY8_PACKED:
01357 //    case IS_CM_RGBA12_UNPACKED:
01358 //    case IS_CM_BGRA12_UNPACKED:
01359 //    case IS_CM_JPEG:
01360     default:
01361       return false;
01362   }
01363 }
01364 
01365 
01366 const std::map<std::string, INT> UEyeCamDriver::COLOR_DICTIONARY = {
01367     { "bayer_rggb8", IS_CM_SENSOR_RAW8 },
01368     { "bayer_rggb10", IS_CM_SENSOR_RAW10 },
01369     { "bayer_rggb12", IS_CM_SENSOR_RAW12 },
01370     { "bayer_rggb16", IS_CM_SENSOR_RAW16 },
01371     { "mono8", IS_CM_MONO8 },
01372     { "mono10", IS_CM_MONO10 },
01373     { "mono12", IS_CM_MONO12 },
01374     { "mono16", IS_CM_MONO16 },
01375     { "rgb8", IS_CM_RGB8_PACKED },
01376     { "bgr8", IS_CM_BGR8_PACKED },
01377     { "rgb10", IS_CM_RGB10_PACKED },
01378     { "bgr10", IS_CM_BGR10_PACKED },
01379     { "rgb10u", IS_CM_RGB10_UNPACKED },
01380     { "bgr10u", IS_CM_BGR10_UNPACKED },
01381     { "rgb12u", IS_CM_RGB12_UNPACKED },
01382     { "bgr12u", IS_CM_BGR12_UNPACKED }
01383 };
01384 
01385 
01386 const INT UEyeCamDriver::name2colormode(const std::string& name) {
01387   const std::map<std::string, INT>::const_iterator iter = COLOR_DICTIONARY.find(name);
01388   if (iter!=COLOR_DICTIONARY.end()) {
01389     return iter->second;
01390   }
01391   else {
01392     return 0;
01393   }
01394 }
01395 
01396 
01397 const std::string UEyeCamDriver::colormode2name(INT mode) {
01398   for (const std::pair<std::string, INT>& value: COLOR_DICTIONARY) {
01399     if (value.second == mode) {
01400       return value.first;
01401     }
01402   }
01403   return std::string();
01404 }
01405 
01406 
01407 const std::function<void*(void*, void*, size_t)> UEyeCamDriver::getUnpackCopyFunc(INT color_mode) {
01408   switch (color_mode) {
01409     case IS_CM_RGB10_PACKED:
01410     case IS_CM_BGR10_PACKED:
01411       return unpackRGB10;
01412     case IS_CM_SENSOR_RAW10:
01413     case IS_CM_MONO10:
01414     case IS_CM_RGB10_UNPACKED:
01415     case IS_CM_BGR10_UNPACKED:
01416       return unpack10u;
01417     case IS_CM_SENSOR_RAW12:
01418     case IS_CM_MONO12:
01419     case IS_CM_RGB12_UNPACKED:
01420     case IS_CM_BGR12_UNPACKED:
01421       return unpack12u;
01422     default:
01423       return memcpy;
01424   }
01425 }
01426 
01427 
01428 void* UEyeCamDriver::unpackRGB10(void* dst, void* src, size_t num) {
01429   // UEye Driver 4.80.2 Linux 64 bit:
01430   // pixel format seems to be
01431   // 00BBBBBB BBBBGGGG GGGGGGRR RRRRRRRR
01432   // instead of documented
01433   // RRRRRRRR RRGGGGGG GGGGBBBB BBBBBB00
01434 
01435   uint32_t pixel;
01436   uint32_t* from = static_cast<uint32_t*>(src);
01437   uint16_t* to = static_cast<uint16_t*>(dst);
01438   // unpack a whole pixels per iteration
01439   for (size_t i=0; i<num/4; ++i) {
01440     pixel = (*from);
01441     to[0] = pixel;
01442     to[0] <<= 6;
01443     pixel >>= 4;
01444     to[1] = pixel;
01445     to[1] &= 0b1111111111000000;
01446     pixel >>= 10;
01447     to[2] = pixel;
01448     to[2] &= 0b1111111111000000;
01449     to+=3;
01450     ++from;
01451   }
01452   return dst;
01453 }
01454 
01455 
01456 void* UEyeCamDriver::unpack10u(void* dst, void* src, size_t num) {
01457   // UEye Driver 4.80.2 Linux 64 bit:
01458   // pixel format seems to be
01459   // 000000CC CCCCCCCC
01460   // instead of documented
01461   // CCCCCCCC CC000000
01462   uint16_t* from = static_cast<uint16_t*>(src);
01463   uint16_t* to = static_cast<uint16_t*>(dst);
01464   // unpack one color per iteration
01465   for (size_t i=0; i<num/2; ++i) {
01466     to[i] = from[i];
01467     to[i] <<= 6;
01468   }
01469   return dst;
01470 }
01471 
01472 
01473 void* UEyeCamDriver::unpack12u(void* dst, void* src, size_t num) {
01474   // UEye Driver 4.80.2 Linux 64 bit:
01475   // pixel format seems to be
01476   // 0000CCCC CCCCCCCC
01477   // instead of documented
01478   // CCCCCCCC CCCC0000
01479   uint16_t* from = static_cast<uint16_t*>(src);
01480   uint16_t* to = static_cast<uint16_t*>(dst);
01481   // unpack one color per iteration
01482   for (size_t i=0; i<num/2; ++i) {
01483     to[i] = from[i];
01484     to[i] <<= 4;
01485   }
01486   return dst;
01487 }
01488 
01489 
01490 bool UEyeCamDriver::getTimestamp(UEYETIME *timestamp) {
01491   UEYEIMAGEINFO ImageInfo;
01492   if(is_GetImageInfo (cam_handle_, cam_buffer_id_, &ImageInfo, sizeof (ImageInfo)) == IS_SUCCESS) {
01493     *timestamp = ImageInfo.TimestampSystem;
01494     return true;
01495   }
01496   return false;
01497 }
01498 
01499 
01500 bool UEyeCamDriver::getClockTick(uint64_t *tick) {
01501   UEYEIMAGEINFO ImageInfo;
01502   if(is_GetImageInfo (cam_handle_, cam_buffer_id_, &ImageInfo, sizeof (ImageInfo)) == IS_SUCCESS) {
01503     *tick = ImageInfo.u64TimestampDevice;
01504     return true;
01505   }
01506   return false;
01507 }
01508 
01509 } // namespace ueye_cam


ueye_cam
Author(s): Anqi Xu
autogenerated on Fri Feb 24 2017 04:14:06