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, 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 #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 "logging_macros.hpp"
00056 
00057 
00058 namespace ueye_cam {
00059 
00060 
00061 #define CAP(val, min, max) \
00062   if (val < min) { \
00063     val = min; \
00064   } else if (val > max) { \
00065     val = max; \
00066   }
00067 
00068 #define IS_SUBSAMPLING_2X (IS_SUBSAMPLING_2X_VERTICAL | IS_SUBSAMPLING_2X_HORIZONTAL)
00069 #define IS_SUBSAMPLING_4X (IS_SUBSAMPLING_4X_VERTICAL | IS_SUBSAMPLING_4X_HORIZONTAL)
00070 #define IS_SUBSAMPLING_8X (IS_SUBSAMPLING_8X_VERTICAL | IS_SUBSAMPLING_8X_HORIZONTAL)
00071 #define IS_SUBSAMPLING_16X (IS_SUBSAMPLING_16X_VERTICAL | IS_SUBSAMPLING_16X_HORIZONTAL)
00072 
00073 #define IS_BINNING_2X (IS_BINNING_2X_VERTICAL | IS_BINNING_2X_HORIZONTAL)
00074 #define IS_BINNING_4X (IS_BINNING_4X_VERTICAL | IS_BINNING_4X_HORIZONTAL)
00075 #define IS_BINNING_8X (IS_BINNING_8X_VERTICAL | IS_BINNING_8X_HORIZONTAL)
00076 #define IS_BINNING_16X (IS_BINNING_16X_VERTICAL | IS_BINNING_16X_HORIZONTAL)
00077 
00078 
00082 class UEyeCamDriver {
00083 public:
00084   constexpr static int ANY_CAMERA = 0;
00085 
00086 
00090   UEyeCamDriver(int cam_ID = ANY_CAMERA, std::string cam_name = "camera");
00091 
00095   virtual ~UEyeCamDriver();
00096 
00104   virtual INT connectCam(int new_cam_ID = -1);
00105 
00111   virtual INT disconnectCam();
00112 
00120   INT loadCamConfig(std::string filename);
00121 
00135   INT setColorMode(std::string mode, bool reallocate_buffer = true);
00136 
00155   INT setResolution(INT& image_width, INT& image_height, INT& image_left,
00156       INT& image_top, bool reallocate_buffer = true);
00157 
00168   INT setSubsampling(int& rate, bool reallocate_buffer = true);
00169 
00180   INT setBinning(int& rate, bool reallocate_buffer = true);
00181 
00192   INT setSensorScaling(double& rate, bool reallocate_buffer = true);
00193 
00211   INT setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
00212       INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost);
00213 
00225   INT setExposure(bool& auto_exposure, double& exposure_ms);
00226 
00238   INT setWhiteBalance(bool& auto_white_balance, INT& red_offset, INT& blue_offset);
00239 
00254   INT setFrameRate(bool& auto_frame_rate, double& frame_rate_hz);
00255 
00264   INT setPixelClockRate(INT& clock_rate_mhz);
00265 
00275   INT setFlashParams(INT& delay_us, UINT& duration_us);
00276 
00296   INT setFreeRunMode();
00297 
00312   INT setExtTriggerMode();
00313 
00320   INT setStandbyMode();
00321 
00328   INT setMirrorUpsideDown(bool flip_horizontal);
00329 
00336   INT setMirrorLeftRight(bool flip_vertical);
00337 
00351   const char* processNextFrame(INT timeout_ms);
00352 
00353   inline bool isConnected() { return (cam_handle_ != (HIDS) 0); };
00354 
00355   inline bool freeRunModeActive() {
00356     return ((cam_handle_ != (HIDS) 0) &&
00357         (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_OFF) &&
00358         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00359   };
00360 
00361   inline bool extTriggerModeActive() {
00362     return ((cam_handle_ != (HIDS) 0) &&
00363         (is_SetExternalTrigger(cam_handle_, IS_GET_EXTERNALTRIGGER) == IS_SET_TRIGGER_HI_LO) &&
00364         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00365   };
00366 
00367   inline bool isCapturing() {
00368     return ((cam_handle_ != (HIDS) 0) &&
00369         (is_CaptureVideo(cam_handle_, IS_GET_LIVE) == TRUE));
00370   };
00371 
00375   const static char* err2str(INT error);
00376 
00377 
00378 protected:
00379   INT reallocateCamBuffer();
00380 
00381   HIDS cam_handle_;
00382   SENSORINFO cam_sensor_info_;
00383   char* cam_buffer_;
00384   int cam_buffer_id_;
00385   INT cam_buffer_pitch_;
00386   unsigned int cam_buffer_size_;
00387   std::string cam_name_;
00388   int cam_id_;
00389   IS_RECT cam_aoi_;
00390   unsigned int cam_subsampling_rate_;
00391   unsigned int cam_binning_rate_;
00392   double cam_sensor_scaling_rate_;
00393   INT bits_per_pixel_;
00394 };
00395 
00396 
00397 }; // namespace ueye_cam
00398 
00399 
00400 #endif /* UEYE_CAM_DRIVER_HPP_ */


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