ueye_cam_driver.hpp
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 #ifndef UEYE_CAM_DRIVER_HPP_
00049 #define UEYE_CAM_DRIVER_HPP_
00050 
00051 
00052 #include <ueye.h>
00053 #include <string>
00054 #include <thread>
00055 #include <functional>
00056 #include "logging_macros.hpp"
00057 
00058 
00059 namespace ueye_cam {
00060 
00061 
00062 #define CAP(val, min, max) \
00063   if (val < min) { \
00064     val = min; \
00065   } else if (val > max) { \
00066     val = max; \
00067   }
00068 
00069 #define IS_SUBSAMPLING_2X (IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL)
00070 #define IS_SUBSAMPLING_4X (IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL)
00071 #define IS_SUBSAMPLING_8X (IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL)
00072 #define IS_SUBSAMPLING_16X (IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL)
00073 
00074 #define IS_BINNING_2X (IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL)
00075 #define IS_BINNING_4X (IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL)
00076 #define IS_BINNING_8X (IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL)
00077 #define IS_BINNING_16X (IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL)
00078 
00079 
00083 class UEyeCamDriver {
00084 public:
00085   constexpr static int ANY_CAMERA = 0;
00086 
00087 
00091   UEyeCamDriver(int cam_ID = ANY_CAMERA, std::string cam_name = "camera");
00092 
00096   virtual ~UEyeCamDriver();
00097 
00105   virtual INT connectCam(int new_cam_ID = -1);
00106 
00112   virtual INT disconnectCam();
00113 
00122   INT loadCamConfig(std::string filename, bool ignore_load_failure = true);
00123 
00137   INT setColorMode(std::string& mode, bool reallocate_buffer = true);
00138 
00157   INT setResolution(INT& image_width, INT& image_height, INT& image_left,
00158       INT& image_top, bool reallocate_buffer = true);
00159 
00170   INT setSubsampling(int& rate, bool reallocate_buffer = true);
00171 
00182   INT setBinning(int& rate, bool reallocate_buffer = true);
00183 
00194   INT setSensorScaling(double& rate, bool reallocate_buffer = true);
00195 
00213   INT setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
00214       INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost);
00215 
00227   INT setExposure(bool& auto_exposure, double& exposure_ms);
00228 
00240   INT setWhiteBalance(bool& auto_white_balance, INT& red_offset, INT& blue_offset);
00241 
00256   INT setFrameRate(bool& auto_frame_rate, double& frame_rate_hz);
00257 
00266   INT setPixelClockRate(INT& clock_rate_mhz);
00267 
00277   INT setFlashParams(INT& delay_us, UINT& duration_us);
00278 
00298   INT setFreeRunMode();
00299 
00314   INT setExtTriggerMode();
00315 
00322   INT setStandbyMode();
00323 
00330   INT setMirrorUpsideDown(bool flip_horizontal);
00331 
00338   INT setMirrorLeftRight(bool flip_vertical);
00339 
00353   const char* processNextFrame(INT timeout_ms);
00354 
00355   inline bool isConnected() { return (cam_handle_ != (HIDS) 0); }
00356 
00357   inline bool freeRunModeActive() {
00358     return ((cam_handle_ != (HIDS) 0) &&
00359         (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_OFF) &&
00360         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00361   }
00362 
00363   inline bool extTriggerModeActive() {
00364     return ((cam_handle_ != (HIDS) 0) &&
00365         (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_HI_LO) &&
00366         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00367   }
00368 
00369   inline bool isCapturing() {
00370     return ((cam_handle_ != (HIDS) 0) &&
00371         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00372   }
00373 
00377   const static char* err2str(INT error);
00378 
00382   const static char* colormode2str(INT mode);
00383 
00387   const static std::string colormode2img_enc(INT mode);
00388 
00392   const static INT colormode2bpp(INT mode);
00393 
00397   const static bool isSupportedColorMode(INT mode);
00398 
00402   const static INT name2colormode(const std::string& name);
00403   const static std::string colormode2name(INT mode);
00404 
00409   const static std::function<void*(void*, void*, size_t)> getUnpackCopyFunc(INT color_mode);
00410   static void* unpackRGB10(void* dst, void* src, size_t num);
00411   static void* unpack10u(void* dst, void* src, size_t num);
00412   static void* unpack12u(void* dst, void* src, size_t num);
00413 
00417   bool getTimestamp(UEYETIME *timestamp);
00418 
00422   bool getClockTick(uint64_t *tick);
00423 
00424 
00425 protected:
00444   virtual INT syncCamConfig(std::string dft_mode_str = "mono8");
00445 
00446 
00447   virtual void handleTimeout() {};
00448 
00449 
00456   INT reallocateCamBuffer();
00457 
00458   const static std::map<std::string, INT> COLOR_DICTIONARY;
00459 
00460   HIDS cam_handle_;
00461   SENSORINFO cam_sensor_info_;
00462   char* cam_buffer_;
00463   int cam_buffer_id_;
00464   INT cam_buffer_pitch_;
00465   unsigned int cam_buffer_size_;
00466   std::string cam_name_;
00467   int cam_id_;
00468   IS_RECT cam_aoi_;
00469   unsigned int cam_subsampling_rate_;
00470   unsigned int cam_binning_rate_;
00471   double cam_sensor_scaling_rate_;
00472   INT color_mode_;
00473   INT bits_per_pixel_;
00474 };
00475 
00476 
00477 } // namespace ueye_cam
00478 
00479 
00480 #endif /* UEYE_CAM_DRIVER_HPP_ */


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