Public Member Functions | Static Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
ueye_cam::UEyeCamDriver Class Reference

#include <ueye_cam_driver.hpp>

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

Public Member Functions

virtual INT connectCam (int new_cam_ID=-1)
 
virtual INT disconnectCam ()
 
bool extTriggerModeActive ()
 
bool freeRunModeActive ()
 
bool getClockTick (uint64_t *tick)
 
bool getTimestamp (UEYETIME *timestamp)
 
bool isCapturing ()
 
bool isConnected ()
 
INT loadCamConfig (std::string filename, bool ignore_load_failure=true)
 
const char * processNextFrame (UINT 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 &auto_exposure_reference, 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 setGpioMode (const INT &gpio, INT &mode, double &pwm_freq, double &pwm_duty_cycle)
 
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 setSoftwareGamma (INT &software_gamma)
 
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 INT colormode2bpp (INT mode)
 
static const std::string colormode2img_enc (INT mode)
 
static const std::string colormode2name (INT mode)
 
static const char * colormode2str (INT mode)
 
static const char * err2str (INT error)
 
static const std::function< void *(void *, void *, size_t)> getUnpackCopyFunc (INT color_mode)
 
static bool isSupportedColorMode (INT mode)
 
static INT name2colormode (const std::string &name)
 
static void * unpack10u (void *dst, void *src, size_t num)
 
static void * unpack12u (void *dst, void *src, size_t num)
 
static void * unpackRGB10 (void *dst, void *src, size_t num)
 

Static Public Attributes

static constexpr int ANY_CAMERA = 0
 

Protected Member Functions

virtual void handleTimeout ()
 
INT reallocateCamBuffer ()
 
virtual INT syncCamConfig (std::string dft_mode_str="mono8")
 

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_
 
INT color_mode_
 

Static Protected Attributes

static const std::map< std::string, INT > COLOR_DICTIONARY
 

Detailed Description

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

Definition at line 83 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 59 of file ueye_cam_driver.cpp.

ueye_cam::UEyeCamDriver::~UEyeCamDriver ( )
virtual

Terminates UEye camera interface.

Definition at line 79 of file ueye_cam_driver.cpp.

Member Function Documentation

INT ueye_cam::UEyeCamDriver::colormode2bpp ( INT  mode)
static

bits per pixel attribute of UEye color mode flag

Definition at line 1384 of file ueye_cam_driver.cpp.

static const std::string ueye_cam::UEyeCamDriver::colormode2img_enc ( INT  mode)
static

translates UEye color mode flag to target ROS image encoding.

const std::string ueye_cam::UEyeCamDriver::colormode2name ( INT  mode)
static

Definition at line 1498 of file ueye_cam_driver.cpp.

const char * ueye_cam::UEyeCamDriver::colormode2str ( INT  mode)
static

Stringifies UEye color mode flag.

Definition at line 1316 of file ueye_cam_driver.cpp.

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 84 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::disconnectCam ( )
virtual

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 154 of file ueye_cam_driver.cpp.

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

Stringifies UEye API error flag.

Definition at line 1219 of file ueye_cam_driver.cpp.

bool ueye_cam::UEyeCamDriver::extTriggerModeActive ( )
inline

Definition at line 386 of file ueye_cam_driver.hpp.

bool ueye_cam::UEyeCamDriver::freeRunModeActive ( )
inline

Definition at line 380 of file ueye_cam_driver.hpp.

bool ueye_cam::UEyeCamDriver::getClockTick ( uint64_t *  tick)

Sets a clock tick indicating the moment of the image capture

Definition at line 1601 of file ueye_cam_driver.cpp.

bool ueye_cam::UEyeCamDriver::getTimestamp ( UEYETIME *  timestamp)

Sets a timestamp indicating the moment of the image capture

Definition at line 1591 of file ueye_cam_driver.cpp.

const std::function< void *(void *, void *, size_t)> ueye_cam::UEyeCamDriver::getUnpackCopyFunc ( INT  color_mode)
static

returns the proper transfer function to translate and copy the camera format pixel buffer either into an 8 or 16 bit unsigned int per channel format.

Definition at line 1508 of file ueye_cam_driver.cpp.

virtual void ueye_cam::UEyeCamDriver::handleTimeout ( )
inlineprotectedvirtual

Reimplemented in ueye_cam::UEyeCamNodelet.

Definition at line 470 of file ueye_cam_driver.hpp.

bool ueye_cam::UEyeCamDriver::isCapturing ( )
inline

Definition at line 392 of file ueye_cam_driver.hpp.

bool ueye_cam::UEyeCamDriver::isConnected ( )
inline

Definition at line 378 of file ueye_cam_driver.hpp.

bool ueye_cam::UEyeCamDriver::isSupportedColorMode ( INT  mode)
static

check if this driver supports the chosen UEye color mode

Definition at line 1428 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::loadCamConfig ( std::string  filename,
bool  ignore_load_failure = true 
)

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

Parameters
filenameRelative or absolute path to UEye camera configuration file.
ignore_load_failureReturn IS_SUCCESS even if failed to load INI file.
Returns
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 177 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::name2colormode ( const std::string &  name)
static

translates ROS name to UEye color mode flag or the other way round.

Definition at line 1487 of file ueye_cam_driver.cpp.

const char * ueye_cam::UEyeCamDriver::processNextFrame ( UINT  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 1042 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::reallocateCamBuffer ( )
protected

(Re-)allocates internal frame buffer after querying current area of interest (resolution), and configures IDS driver to use this buffer.

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

Definition at line 1157 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 367 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: see UEyeCamDriver::COLOR_DICTIONARY 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 204 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setExposure ( bool &  auto_exposure,
double &  auto_exposure_reference,
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.
auto_exposure_referencesets the reference value for the auto_exposure controller.
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 587 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setExtTriggerMode ( )

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 912 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 785 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 682 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setFreeRunMode ( )

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 869 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 490 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setGpioMode ( const INT &  gpio,
INT &  mode,
double &  pwm_freq,
double &  pwm_duty_cycle 
)

Sets the mode for the GPIO pins.

Parameters
GPIOpin to be set {GPIO1: 1, GPIO2: 2}.
modefor GPIO pin {0: input, 1: output low, 2: output high, 3: flash, 4: pwm output, 5: trigger input}.
pwm_freqfrequency if pwm output is selected as the mode
pwm_duty_cycleduty cycle if pwm output is selected as the mode
Returns
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 824 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 964 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 951 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 738 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 241 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 439 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setSoftwareGamma ( INT &  software_gamma)

Updates current camera handle's software gamma to specified parameter.

According to ids this is only possible when the color mode is debayered by the ids driver

Parameters
software_gammagamma value in percentage
Returns
IS_SUCCESS if successful, error flag otherwise (see err2str).

Definition at line 562 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::setStandbyMode ( )

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 977 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 295 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 641 of file ueye_cam_driver.cpp.

INT ueye_cam::UEyeCamDriver::syncCamConfig ( std::string  dft_mode_str = "mono8")
protectedvirtual

Queries current camera handle's configuration (color mode, (area of interest / resolution, sensor scaling rate, subsampling rate, binning rate) to synchronize with this class's internal member values, then force-updates to default settings if current ones are not supported by this driver wrapper (ueye_cam), and finally force (re-)allocates internal frame buffer.

This function is intended to be called internally, after opening a camera handle (in connectCam()) or after loading a UEye camera configuration file (in loadCamConfig()), where the camera may be already operating with a non-supported setting.

Parameters
dft_mode_strdefault color mode to switch to, if current color mode is not supported by this driver wrapper. Valid values: {"rgb8", "bgr8", "mono8", "bayer_rggb8"}
Returns
IS_SUCCESS if successful, error flag otherwise (see err2str).

Reimplemented in ueye_cam::UEyeCamNodelet.

Definition at line 1067 of file ueye_cam_driver.cpp.

void * ueye_cam::UEyeCamDriver::unpack10u ( void *  dst,
void *  src,
size_t  num 
)
static

Definition at line 1557 of file ueye_cam_driver.cpp.

void * ueye_cam::UEyeCamDriver::unpack12u ( void *  dst,
void *  src,
size_t  num 
)
static

Definition at line 1574 of file ueye_cam_driver.cpp.

void * ueye_cam::UEyeCamDriver::unpackRGB10 ( void *  dst,
void *  src,
size_t  num 
)
static

Definition at line 1529 of file ueye_cam_driver.cpp.

Member Data Documentation

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

Definition at line 85 of file ueye_cam_driver.hpp.

INT ueye_cam::UEyeCamDriver::bits_per_pixel_
protected

Definition at line 496 of file ueye_cam_driver.hpp.

IS_RECT ueye_cam::UEyeCamDriver::cam_aoi_
protected

Definition at line 491 of file ueye_cam_driver.hpp.

unsigned int ueye_cam::UEyeCamDriver::cam_binning_rate_
protected

Definition at line 493 of file ueye_cam_driver.hpp.

char* ueye_cam::UEyeCamDriver::cam_buffer_
protected

Definition at line 485 of file ueye_cam_driver.hpp.

int ueye_cam::UEyeCamDriver::cam_buffer_id_
protected

Definition at line 486 of file ueye_cam_driver.hpp.

INT ueye_cam::UEyeCamDriver::cam_buffer_pitch_
protected

Definition at line 487 of file ueye_cam_driver.hpp.

unsigned int ueye_cam::UEyeCamDriver::cam_buffer_size_
protected

Definition at line 488 of file ueye_cam_driver.hpp.

HIDS ueye_cam::UEyeCamDriver::cam_handle_
protected

Definition at line 483 of file ueye_cam_driver.hpp.

int ueye_cam::UEyeCamDriver::cam_id_
protected

Definition at line 490 of file ueye_cam_driver.hpp.

std::string ueye_cam::UEyeCamDriver::cam_name_
protected

Definition at line 489 of file ueye_cam_driver.hpp.

SENSORINFO ueye_cam::UEyeCamDriver::cam_sensor_info_
protected

Definition at line 484 of file ueye_cam_driver.hpp.

double ueye_cam::UEyeCamDriver::cam_sensor_scaling_rate_
protected

Definition at line 494 of file ueye_cam_driver.hpp.

unsigned int ueye_cam::UEyeCamDriver::cam_subsampling_rate_
protected

Definition at line 492 of file ueye_cam_driver.hpp.

const std::map< std::string, INT > ueye_cam::UEyeCamDriver::COLOR_DICTIONARY
staticprotected
Initial value:
= {
{ "bayer_rggb8", IS_CM_SENSOR_RAW8 },
{ "bayer_rggb10", IS_CM_SENSOR_RAW10 },
{ "bayer_rggb12", IS_CM_SENSOR_RAW12 },
{ "bayer_rggb16", IS_CM_SENSOR_RAW16 },
{ "mono8", IS_CM_MONO8 },
{ "mono10", IS_CM_MONO10 },
{ "mono12", IS_CM_MONO12 },
{ "mono16", IS_CM_MONO16 },
{ "rgb8", IS_CM_RGB8_PACKED },
{ "bgr8", IS_CM_BGR8_PACKED },
{ "rgb10", IS_CM_RGB10_PACKED },
{ "bgr10", IS_CM_BGR10_PACKED },
{ "rgb10u", IS_CM_RGB10_UNPACKED },
{ "bgr10u", IS_CM_BGR10_UNPACKED },
{ "rgb12u", IS_CM_RGB12_UNPACKED },
{ "bgr12u", IS_CM_BGR12_UNPACKED }
}

Definition at line 481 of file ueye_cam_driver.hpp.

INT ueye_cam::UEyeCamDriver::color_mode_
protected

Definition at line 495 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 Fri Jan 22 2021 03:34:13