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

#include <ueye_cam_nodelet.hpp>

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

Public Member Functions

void configCallback (ueye_cam::UEyeCamConfig &config, uint32_t level)
 
virtual void onInit ()
 
 UEyeCamNodelet ()
 
virtual ~UEyeCamNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 
- Public Member Functions inherited from ueye_cam::UEyeCamDriver
virtual INT connectCam (int new_cam_ID=-1)
 
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 Attributes

const static std::string DEFAULT_CAMERA_NAME = "camera"
 
const static std::string DEFAULT_CAMERA_TOPIC = "image_raw"
 
const static std::string DEFAULT_COLOR_MODE = ""
 
constexpr static double DEFAULT_EXPOSURE = 33.0
 
constexpr static int DEFAULT_FLASH_DURATION = 1000
 
const static std::string DEFAULT_FRAME_NAME = "camera"
 
constexpr static double DEFAULT_FRAME_RATE = 10.0
 
constexpr static int DEFAULT_IMAGE_HEIGHT = 480
 
constexpr static int DEFAULT_IMAGE_WIDTH = 640
 
constexpr static int DEFAULT_PIXEL_CLOCK = 25
 
const static std::string DEFAULT_TIMEOUT_TOPIC = "timeout_count"
 
constexpr static unsigned int RECONFIGURE_CLOSE = 3
 
constexpr static unsigned int RECONFIGURE_RUNNING = 0
 
constexpr static unsigned int RECONFIGURE_STOP = 1
 
- Static Public Attributes inherited from ueye_cam::UEyeCamDriver
constexpr static int ANY_CAMERA = 0
 

Protected Member Functions

virtual INT connectCam ()
 
virtual INT disconnectCam ()
 
bool fillMsgData (sensor_msgs::Image &img) const
 
void frameGrabLoop ()
 
ros::Time getImageTickTimestamp ()
 
ros::Time getImageTimestamp ()
 
virtual void handleTimeout ()
 
void loadIntrinsicsFile ()
 
INT parseROSParams (ros::NodeHandle &local_nh)
 
INT queryCamParams ()
 
bool saveIntrinsicsFile ()
 
bool setCamInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
 
void startFrameGrabber ()
 
void stopFrameGrabber ()
 
virtual INT syncCamConfig (std::string dft_mode_str="mono8")
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Member Functions inherited from ueye_cam::UEyeCamDriver
INT reallocateCamBuffer ()
 

Protected Attributes

std::string cam_intr_filename_
 
ueye_cam::UEyeCamConfig cam_params_
 
std::string cam_params_filename_
 
std::string cam_topic_
 
bool cfg_sync_requested_
 
bool frame_grab_alive_
 
std::thread frame_grab_thread_
 
std::string frame_name_
 
uint64_t init_clock_tick_
 
ros::Time init_publish_time_
 
ros::Time init_ros_time_
 
boost::mutex output_rate_mutex_
 
uint64_t prev_output_frame_idx_
 
sensor_msgs::CameraInfo ros_cam_info_
 
image_transport::CameraPublisher ros_cam_pub_
 
ReconfigureServerros_cfg_
 
boost::recursive_mutex ros_cfg_mutex_
 
unsigned int ros_frame_count_
 
sensor_msgs::Image ros_image_
 
ros::ServiceServer set_cam_info_srv_
 
unsigned long long int timeout_count_
 
ros::Publisher timeout_pub_
 
std::string timeout_topic_
 
- Protected Attributes inherited from ueye_cam::UEyeCamDriver
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

const static std::map< INT, std::string > ENCODING_DICTIONARY
 
- Static Protected Attributes inherited from ueye_cam::UEyeCamDriver
const static std::map< std::string, INT > COLOR_DICTIONARY
 

Additional Inherited Members

- Static Public Member Functions inherited from ueye_cam::UEyeCamDriver
static INT colormode2bpp (INT mode)
 
const static std::string colormode2img_enc (INT mode)
 
const static std::string colormode2name (INT mode)
 
const static char * colormode2str (INT mode)
 
const static char * err2str (INT error)
 
const static 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)
 

Detailed Description

ROS interface nodelet for UEye camera API from IDS Imaging Development Systems GMBH.

Definition at line 117 of file ueye_cam_nodelet.hpp.

Constructor & Destructor Documentation

◆ UEyeCamNodelet()

ueye_cam::UEyeCamNodelet::UEyeCamNodelet ( )

Definition at line 76 of file ueye_cam_nodelet.cpp.

◆ ~UEyeCamNodelet()

ueye_cam::UEyeCamNodelet::~UEyeCamNodelet ( )
virtual

Definition at line 129 of file ueye_cam_nodelet.cpp.

Member Function Documentation

◆ configCallback()

void ueye_cam::UEyeCamNodelet::configCallback ( ueye_cam::UEyeCamConfig &  config,
uint32_t  level 
)

Handles callbacks from dynamic_reconfigure.

Definition at line 633 of file ueye_cam_nodelet.cpp.

◆ connectCam()

INT ueye_cam::UEyeCamNodelet::connectCam ( )
protectedvirtual

Initializes the camera handle, loads UEye INI configuration, refreshes parameters from camera, loads and sets static ROS parameters, and starts the frame grabber thread.

Definition at line 975 of file ueye_cam_nodelet.cpp.

◆ disconnectCam()

INT ueye_cam::UEyeCamNodelet::disconnectCam ( )
protectedvirtual

Stops the frame grabber thread, closes the camera handle, and releases all local variables.

Reimplemented from ueye_cam::UEyeCamDriver.

Definition at line 999 of file ueye_cam_nodelet.cpp.

◆ fillMsgData()

bool ueye_cam::UEyeCamNodelet::fillMsgData ( sensor_msgs::Image &  img) const
protected

Transfers the current frame content into given sensor_msgs::Image, therefore writes the fields width, height, encoding, step and data of img.

Definition at line 1230 of file ueye_cam_nodelet.cpp.

◆ frameGrabLoop()

void ueye_cam::UEyeCamNodelet::frameGrabLoop ( )
protected

Main ROS interface "spin" loop.

Definition at line 1023 of file ueye_cam_nodelet.cpp.

◆ getImageTickTimestamp()

ros::Time ueye_cam::UEyeCamNodelet::getImageTickTimestamp ( )
protected

Returns image's timestamp based on device's internal clock or current wall time if driver call fails.

Definition at line 1320 of file ueye_cam_nodelet.cpp.

◆ getImageTimestamp()

ros::Time ueye_cam::UEyeCamNodelet::getImageTimestamp ( )
protected

Returns image's timestamp or current wall time if driver call fails.

Definition at line 1296 of file ueye_cam_nodelet.cpp.

◆ handleTimeout()

void ueye_cam::UEyeCamNodelet::handleTimeout ( )
protectedvirtual

Reimplemented from ueye_cam::UEyeCamDriver.

Definition at line 1330 of file ueye_cam_nodelet.cpp.

◆ loadIntrinsicsFile()

void ueye_cam::UEyeCamNodelet::loadIntrinsicsFile ( )
protected

Loads the camera's intrinsic parameters from camIntrFilename.

Definition at line 1275 of file ueye_cam_nodelet.cpp.

◆ onInit()

void ueye_cam::UEyeCamNodelet::onInit ( )
virtual

Initializes ROS environment, loads static ROS parameters, initializes UEye camera, and starts live capturing / frame grabbing thread.

Implements nodelet::Nodelet.

Definition at line 142 of file ueye_cam_nodelet.cpp.

◆ parseROSParams()

INT ueye_cam::UEyeCamNodelet::parseROSParams ( ros::NodeHandle local_nh)
protected

Loads, validates, and updates static ROS parameters.

Definition at line 220 of file ueye_cam_nodelet.cpp.

◆ queryCamParams()

INT ueye_cam::UEyeCamNodelet::queryCamParams ( )
protected

Reads parameter values from currently selected camera.

Definition at line 834 of file ueye_cam_nodelet.cpp.

◆ saveIntrinsicsFile()

bool ueye_cam::UEyeCamNodelet::saveIntrinsicsFile ( )
protected

Saves the camera's intrinsic parameters to camIntrFilename.

Definition at line 1287 of file ueye_cam_nodelet.cpp.

◆ setCamInfo()

bool ueye_cam::UEyeCamNodelet::setCamInfo ( sensor_msgs::SetCameraInfo::Request &  req,
sensor_msgs::SetCameraInfo::Response &  rsp 
)
protected

(ROS Service) Updates the camera's intrinsic parameters over the ROS topic, and saves the parameters to a flatfile.

Definition at line 1011 of file ueye_cam_nodelet.cpp.

◆ startFrameGrabber()

void ueye_cam::UEyeCamNodelet::startFrameGrabber ( )
protected

Definition at line 1197 of file ueye_cam_nodelet.cpp.

◆ stopFrameGrabber()

void ueye_cam::UEyeCamNodelet::stopFrameGrabber ( )
protected

Definition at line 1203 of file ueye_cam_nodelet.cpp.

◆ syncCamConfig()

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

Calls UEyeCamDriver::syncCamConfig(), then updates ROS camera info and ROS image settings.

Reimplemented from ueye_cam::UEyeCamDriver.

Definition at line 801 of file ueye_cam_nodelet.cpp.

Member Data Documentation

◆ cam_intr_filename_

std::string ueye_cam::UEyeCamNodelet::cam_intr_filename_
protected

Definition at line 246 of file ueye_cam_nodelet.hpp.

◆ cam_params_

ueye_cam::UEyeCamConfig ueye_cam::UEyeCamNodelet::cam_params_
protected

Definition at line 248 of file ueye_cam_nodelet.hpp.

◆ cam_params_filename_

std::string ueye_cam::UEyeCamNodelet::cam_params_filename_
protected

Definition at line 247 of file ueye_cam_nodelet.hpp.

◆ cam_topic_

std::string ueye_cam::UEyeCamNodelet::cam_topic_
protected

Definition at line 244 of file ueye_cam_nodelet.hpp.

◆ cfg_sync_requested_

bool ueye_cam::UEyeCamNodelet::cfg_sync_requested_
protected

Definition at line 232 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_CAMERA_NAME

const std::string ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera"
static

Definition at line 130 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_CAMERA_TOPIC

const std::string ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw"
static

Definition at line 131 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_COLOR_MODE

const std::string ueye_cam::UEyeCamNodelet::DEFAULT_COLOR_MODE = ""
static

Definition at line 133 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_EXPOSURE

constexpr static double ueye_cam::UEyeCamNodelet::DEFAULT_EXPOSURE = 33.0
staticconstexpr

Definition at line 124 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_FLASH_DURATION

constexpr static int ueye_cam::UEyeCamNodelet::DEFAULT_FLASH_DURATION = 1000
staticconstexpr

Definition at line 127 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_FRAME_NAME

const std::string ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera"
static

Definition at line 129 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_FRAME_RATE

constexpr static double ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_RATE = 10.0
staticconstexpr

Definition at line 125 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_IMAGE_HEIGHT

constexpr static int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_HEIGHT = 480
staticconstexpr

Definition at line 123 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_IMAGE_WIDTH

constexpr static int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_WIDTH = 640
staticconstexpr

Definition at line 122 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_PIXEL_CLOCK

constexpr static int ueye_cam::UEyeCamNodelet::DEFAULT_PIXEL_CLOCK = 25
staticconstexpr

Definition at line 126 of file ueye_cam_nodelet.hpp.

◆ DEFAULT_TIMEOUT_TOPIC

const std::string ueye_cam::UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC = "timeout_count"
static

Definition at line 132 of file ueye_cam_nodelet.hpp.

◆ ENCODING_DICTIONARY

const std::map< INT, std::string > ueye_cam::UEyeCamNodelet::ENCODING_DICTIONARY
staticprotected
Initial value:
= {
{ IS_CM_RGB8_PACKED, sensor_msgs::image_encodings::RGB8 },
{ IS_CM_BGR8_PACKED, sensor_msgs::image_encodings::BGR8 },
{ IS_CM_RGB10_PACKED, sensor_msgs::image_encodings::RGB16 },
{ IS_CM_BGR10_PACKED, sensor_msgs::image_encodings::BGR16 },
{ IS_CM_RGB10_UNPACKED, sensor_msgs::image_encodings::RGB16 },
{ IS_CM_BGR10_UNPACKED, sensor_msgs::image_encodings::BGR16 },
{ IS_CM_RGB12_UNPACKED, sensor_msgs::image_encodings::RGB16 },
{ IS_CM_BGR12_UNPACKED, sensor_msgs::image_encodings::BGR16 }
}

Definition at line 207 of file ueye_cam_nodelet.hpp.

◆ frame_grab_alive_

bool ueye_cam::UEyeCamNodelet::frame_grab_alive_
protected

Definition at line 228 of file ueye_cam_nodelet.hpp.

◆ frame_grab_thread_

std::thread ueye_cam::UEyeCamNodelet::frame_grab_thread_
protected

Definition at line 227 of file ueye_cam_nodelet.hpp.

◆ frame_name_

std::string ueye_cam::UEyeCamNodelet::frame_name_
protected

Definition at line 243 of file ueye_cam_nodelet.hpp.

◆ init_clock_tick_

uint64_t ueye_cam::UEyeCamNodelet::init_clock_tick_
protected

Definition at line 251 of file ueye_cam_nodelet.hpp.

◆ init_publish_time_

ros::Time ueye_cam::UEyeCamNodelet::init_publish_time_
protected

Definition at line 253 of file ueye_cam_nodelet.hpp.

◆ init_ros_time_

ros::Time ueye_cam::UEyeCamNodelet::init_ros_time_
protected

Definition at line 250 of file ueye_cam_nodelet.hpp.

◆ output_rate_mutex_

boost::mutex ueye_cam::UEyeCamNodelet::output_rate_mutex_
protected

Definition at line 255 of file ueye_cam_nodelet.hpp.

◆ prev_output_frame_idx_

uint64_t ueye_cam::UEyeCamNodelet::prev_output_frame_idx_
protected

Definition at line 254 of file ueye_cam_nodelet.hpp.

◆ RECONFIGURE_CLOSE

constexpr static unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_CLOSE = 3
staticconstexpr

Definition at line 121 of file ueye_cam_nodelet.hpp.

◆ RECONFIGURE_RUNNING

constexpr static unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_RUNNING = 0
staticconstexpr

Definition at line 119 of file ueye_cam_nodelet.hpp.

◆ RECONFIGURE_STOP

constexpr static unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_STOP = 1
staticconstexpr

Definition at line 120 of file ueye_cam_nodelet.hpp.

◆ ros_cam_info_

sensor_msgs::CameraInfo ueye_cam::UEyeCamNodelet::ros_cam_info_
protected

Definition at line 236 of file ueye_cam_nodelet.hpp.

◆ ros_cam_pub_

image_transport::CameraPublisher ueye_cam::UEyeCamNodelet::ros_cam_pub_
protected

Definition at line 234 of file ueye_cam_nodelet.hpp.

◆ ros_cfg_

ReconfigureServer* ueye_cam::UEyeCamNodelet::ros_cfg_
protected

Definition at line 230 of file ueye_cam_nodelet.hpp.

◆ ros_cfg_mutex_

boost::recursive_mutex ueye_cam::UEyeCamNodelet::ros_cfg_mutex_
protected

Definition at line 231 of file ueye_cam_nodelet.hpp.

◆ ros_frame_count_

unsigned int ueye_cam::UEyeCamNodelet::ros_frame_count_
protected

Definition at line 237 of file ueye_cam_nodelet.hpp.

◆ ros_image_

sensor_msgs::Image ueye_cam::UEyeCamNodelet::ros_image_
protected

Definition at line 235 of file ueye_cam_nodelet.hpp.

◆ set_cam_info_srv_

ros::ServiceServer ueye_cam::UEyeCamNodelet::set_cam_info_srv_
protected

Definition at line 241 of file ueye_cam_nodelet.hpp.

◆ timeout_count_

unsigned long long int ueye_cam::UEyeCamNodelet::timeout_count_
protected

Definition at line 239 of file ueye_cam_nodelet.hpp.

◆ timeout_pub_

ros::Publisher ueye_cam::UEyeCamNodelet::timeout_pub_
protected

Definition at line 238 of file ueye_cam_nodelet.hpp.

◆ timeout_topic_

std::string ueye_cam::UEyeCamNodelet::timeout_topic_
protected

Definition at line 245 of file ueye_cam_nodelet.hpp.


The documentation for this class was generated from the following files:
sensor_msgs::image_encodings::BAYER_RGGB8
const std::string BAYER_RGGB8
sensor_msgs::image_encodings::RGB8
const std::string RGB8
sensor_msgs::image_encodings::BGR16
const std::string BGR16
sensor_msgs::image_encodings::MONO8
const std::string MONO8
sensor_msgs::image_encodings::MONO16
const std::string MONO16
sensor_msgs::image_encodings::BGR8
const std::string BGR8
sensor_msgs::image_encodings::RGB16
const std::string RGB16
sensor_msgs::image_encodings::BAYER_RGGB16
const std::string BAYER_RGGB16


ueye_cam
Author(s): Anqi Xu
autogenerated on Tue Mar 8 2022 03:50:09