Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
ueye_cam::UEyeCamDriver Class Reference

#include <ueye_cam_driver.hpp>

Inheritance diagram for ueye_cam::UEyeCamDriver:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual INT connectCam (int new_cam_ID=-1)
virtual INT disconnectCam ()
bool extTriggerModeActive ()
bool freeRunModeActive ()
bool isCapturing ()
bool isConnected ()
INT loadCamConfig (std::string filename)
const char * processNextFrame (INT timeout_ms)
INT setBinning (int &rate, bool reallocate_buffer=true)
INT setColorMode (std::string mode, bool reallocate_buffer=true)
INT setExposure (bool &auto_exposure, double &exposure_ms)
INT setExtTriggerMode ()
INT setFlashParams (INT &delay_us, UINT &duration_us)
INT setFrameRate (bool &auto_frame_rate, double &frame_rate_hz)
INT setFreeRunMode ()
INT setGain (bool &auto_gain, INT &master_gain_prc, INT &red_gain_prc, INT &green_gain_prc, INT &blue_gain_prc, bool &gain_boost)
INT setMirrorLeftRight (bool flip_vertical)
INT setMirrorUpsideDown (bool flip_horizontal)
INT setPixelClockRate (INT &clock_rate_mhz)
INT setResolution (INT &image_width, INT &image_height, INT &image_left, INT &image_top, bool reallocate_buffer=true)
INT setSensorScaling (double &rate, bool reallocate_buffer=true)
INT setStandbyMode ()
INT setSubsampling (int &rate, bool reallocate_buffer=true)
INT setWhiteBalance (bool &auto_white_balance, INT &red_offset, INT &blue_offset)
 UEyeCamDriver (int cam_ID=ANY_CAMERA, std::string cam_name="camera")
virtual ~UEyeCamDriver ()

Static Public Member Functions

static const char * err2str (INT error)

Static Public Attributes

static constexpr int ANY_CAMERA = 0

Protected Member Functions

INT reallocateCamBuffer ()

Protected Attributes

INT bits_per_pixel_
IS_RECT cam_aoi_
unsigned int cam_binning_rate_
char * cam_buffer_
int cam_buffer_id_
INT cam_buffer_pitch_
unsigned int cam_buffer_size_
HIDS cam_handle_
int cam_id_
std::string cam_name_
SENSORINFO cam_sensor_info_
double cam_sensor_scaling_rate_
unsigned int cam_subsampling_rate_

Detailed Description

Thin wrapper for UEye camera API from IDS Imaging Development Systems GMBH.

Definition at line 82 of file ueye_cam_driver.hpp.


Constructor & Destructor Documentation

ueye_cam::UEyeCamDriver::UEyeCamDriver ( int  cam_ID = ANY_CAMERA,
std::string  cam_name = "camera" 
)

Initializes member variables.

Definition at line 57 of file ueye_cam_driver.cpp.

Terminates UEye camera interface.

Definition at line 76 of file ueye_cam_driver.cpp.


Member Function Documentation

INT ueye_cam::UEyeCamDriver::connectCam ( int  new_cam_ID = -1) [virtual]

Initializes and loads the UEye camera handle.

Parameters:
new_cam_IDIf set to -1, then uses existing camera ID.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 81 of file ueye_cam_driver.cpp.

Terminates and releases the UEye camera handle.

Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Reimplemented in ueye_cam::UEyeCamNodelet.

Definition at line 136 of file ueye_cam_driver.cpp.

const char * ueye_cam::UEyeCamDriver::err2str ( INT  error) [static]

Stringifies UEye API error flag.

Definition at line 949 of file ueye_cam_driver.cpp.

Definition at line 361 of file ueye_cam_driver.hpp.

Definition at line 355 of file ueye_cam_driver.hpp.

Definition at line 367 of file ueye_cam_driver.hpp.

Definition at line 353 of file ueye_cam_driver.hpp.

INT ueye_cam::UEyeCamDriver::loadCamConfig ( std::string  filename)

Loads UEye camera parameter configuration INI file into current camera's settings.

Parameters:
filenameRelative or absolute path to UEye camera configuration file.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 159 of file ueye_cam_driver.cpp.

const char * ueye_cam::UEyeCamDriver::processNextFrame ( INT  timeout_ms)

Waits for next frame to be available, then returns pointer to frame if successful. This function should only be called when the camera is in live capture mode. Since this function will block until the next frame is available, it can be used in a loop, without additional delays, to repeatedly query frames from the camera at the maximum rate possible given current camera settings.

Parameters:
timeout_msTimeout duration while waiting for next frame event.
Returns:
Pointer to raw image buffer if successful, NULL otherwise. WARNING: image buffer contents may change during capture, or may become invalid after calling other functions!

Definition at line 890 of file ueye_cam_driver.cpp.

Definition at line 907 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setBinning ( int &  rate,
bool  reallocate_buffer = true 
)

Updates current camera handle's binning rate.

Parameters:
rateDesired binning rate.
reallocate_bufferWhether to auto-reallocate buffer or not after changing parameter. If set to false, remember to reallocate_buffer via another function or via reallocateCamBuffer() manually!
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 347 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setColorMode ( std::string  mode,
bool  reallocate_buffer = true 
)

Updates current camera handle's color mode and re-initializes internal frame buffer. This function will stop live capture automatically if necessary.

Parameters:
modeColor mode string. Valid values: {"rgb8", "mono8", "bayer_rggb8"}. Certain values may not be available for a given camera model.
reallocate_bufferWhether to auto-reallocate buffer or not after changing parameter. If set to false, remember to reallocate_buffer via another function or via reallocateCamBuffer() manually!
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 200 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setExposure ( bool &  auto_exposure,
double &  exposure_ms 
)

Updates current camera handle's exposure / shutter either to auto mode, or to specified manual parameters.

Parameters:
auto_exposureUpdates camera's hardware auto shutter / auto shutter mode. Will be deactivated if camera does not support mode.
exposure_msManual exposure setting, in ms. Valid value range depends on current camera pixel clock rate.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 538 of file ueye_cam_driver.cpp.

Sets current camera to external trigger mode, where a HI to LO falling-edge signal on the digital input pin of the camera will trigger the camera to capture a frame. This function also resets the digital output pin to always be LO.

Note that this function only sets the mode. Frames are then grabbed by calling processNextFrame().

IMPLEMENTATION DETAIL: currently this function supports falling-edge trigger only, since our camera (UI-1246LE) only supports this mode

Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 783 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setFlashParams ( INT &  delay_us,
UINT &  duration_us 
)

Updates the flash signal's delay (from start of exposure) and duration. The flash signal is routed to the digital output pin by default in setFreeRunMode(), and can act as a triggering signal for driving other cameras configured as setExtTriggerMode().

Note that setting flash parameters by itself may not have an effect, if the flash output is not enabled via is_IO().

Definition at line 707 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setFrameRate ( bool &  auto_frame_rate,
double &  frame_rate_hz 
)

Updates current camera handle's frame rate either to auto mode, or to specified manual parameters.

Enabling auto frame rate mode requires that auto shutter mode be enabled. Enabling auto frame rate mode will disable auto gain mode.

Parameters:
auto_frame_rateUpdates camera's hardware auto frame rate / auto frame mode mode. Will be deactivated if camera does not support mode.
frame_rate_hzDesired frame rate, in Hz / frames per second. Valid value range depends on current camera pixel clock rate.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 625 of file ueye_cam_driver.cpp.

Sets current camera to start capturing frames to internal buffer repeatedly. This function also pre-configures the camera to operate in free-run, non-triggered mode, and further attempts to enable the digital output pin to raise to HI during exposure (a.k.a. flash signal, which is useful for triggering other cameras).

Note that this function only sets the mode. Frames are grabbed by calling processNextFrame().

IMPLEMENTATION DETAIL: the flash output signal is set to active-high, so that multiple flash outputs from different cameras can be connected to an OR combination gate to allow any camera to emit the flash trigger. In contrast, in active-low mode, any de-activated camera will output LOW, which would dominate over the triggering signals at the NAND combination gate.

Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 746 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setGain ( bool &  auto_gain,
INT &  master_gain_prc,
INT &  red_gain_prc,
INT &  green_gain_prc,
INT &  blue_gain_prc,
bool &  gain_boost 
)

Updates current camera handle's gain either to auto mode, or to specified manual parameters.

Auto gain mode is disabled if auto frame rate mode is enabled.

Parameters:
auto_gainUpdates camera's hardware auto gain / auto gain mode. Will be deactivated if camera does not support mode.
master_gain_prcManual master gain percentage.
red_gain_prcManual red channel gain percentage.
green_gain_prcManual green channel gain percentage.
blue_gain_prcManual blue channel gain percentage.
gain_boostSets the gain boost. This parameter is independent of auto/manual gain mode.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 465 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setMirrorLeftRight ( bool  flip_vertical)

Mirrors the camera image left to right

Parameters:
flip_verticalWheter to flip the image left to right or not.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 825 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setMirrorUpsideDown ( bool  flip_horizontal)

Mirrors the camera image upside down

Parameters:
flip_horizontalWheter to flip the image upside down or not.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 813 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setPixelClockRate ( INT &  clock_rate_mhz)

Updates current camera handle's pixel clock rate.

Parameters:
clock_rate_mhzDesired pixel clock rate, in MHz. Valid value range depends on camera model.
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 679 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setResolution ( INT &  image_width,
INT &  image_height,
INT &  image_left,
INT &  image_top,
bool  reallocate_buffer = true 
)

Updates current camera handle's sensor resolution and area of interest. This function will stop live capture automatically if necessary.

Parameters:
image_widthDesired width for area of interest / image. Will be automatically bounded by valid range for current camera.
image_heightDesired height for area of interest / image. Will be automatically bounded by valid range for current camera.
image_leftDesired left pixel offset for area of interest / image. Set to -1 to auto-center.
image_topDesired top pixel offset for area of interest / image. Set to -1 to auto-center.
reallocate_bufferWhether to auto-reallocate buffer or not after changing parameter. If set to false, remember to reallocate_buffer via another function or via reallocateCamBuffer() manually!
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 235 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setSensorScaling ( double &  rate,
bool  reallocate_buffer = true 
)

Updates current camera handle's internal image scaling rate.

Parameters:
rateDesired internal image scaling rate.
reallocate_bufferWhether to auto-reallocate buffer or not after changing parameter. If set to false, remember to reallocate_buffer via another function or via reallocateCamBuffer() manually!
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 415 of file ueye_cam_driver.cpp.

Disables either free-run or external trigger mode, and sets the current camera to standby mode.

Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 837 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setSubsampling ( int &  rate,
bool  reallocate_buffer = true 
)

Updates current camera handle's subsampling rate.

Parameters:
rateDesired subsampling rate.
reallocate_bufferWhether to auto-reallocate buffer or not after changing parameter. If set to false, remember to reallocate_buffer via another function or via reallocateCamBuffer() manually!
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 279 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setWhiteBalance ( bool &  auto_white_balance,
INT &  red_offset,
INT &  blue_offset 
)

Enables or disables the current camera handle's auto white balance mode, and configures auto white balance channel offset parameters.

Parameters:
auto_white_balanceUpdates camera's hardware auto white balance / auto white balance mode. Will be deactivated if camera does not support mode.
red_offsetRed channel offset in auto white balance mode. Range: [-50, 50]
blue_offsetBlue channel offset in auto white balance mode. Range: [-50, 50]
Returns:
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 585 of file ueye_cam_driver.cpp.


Member Data Documentation

constexpr int ueye_cam::UEyeCamDriver::ANY_CAMERA = 0 [static]

Definition at line 84 of file ueye_cam_driver.hpp.

Definition at line 393 of file ueye_cam_driver.hpp.

IS_RECT ueye_cam::UEyeCamDriver::cam_aoi_ [protected]

Definition at line 389 of file ueye_cam_driver.hpp.

Definition at line 391 of file ueye_cam_driver.hpp.

Definition at line 383 of file ueye_cam_driver.hpp.

Definition at line 384 of file ueye_cam_driver.hpp.

Definition at line 385 of file ueye_cam_driver.hpp.

Definition at line 386 of file ueye_cam_driver.hpp.

Definition at line 381 of file ueye_cam_driver.hpp.

Definition at line 388 of file ueye_cam_driver.hpp.

std::string ueye_cam::UEyeCamDriver::cam_name_ [protected]

Definition at line 387 of file ueye_cam_driver.hpp.

Definition at line 382 of file ueye_cam_driver.hpp.

Definition at line 392 of file ueye_cam_driver.hpp.

Definition at line 390 of file ueye_cam_driver.hpp.


The documentation for this class was generated from the following files:


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