#include <ueye_cam_nodelet.hpp>
Public Member Functions | |
void | configCallback (ueye_cam::UEyeCamConfig &config, uint32_t level) |
virtual void | onInit () |
UEyeCamNodelet () | |
virtual | ~UEyeCamNodelet () |
![]() | |
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 () |
![]() | |
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 |
![]() | |
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") |
![]() | |
ros::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
![]() | |
INT | reallocateCamBuffer () |
Static Protected Attributes | |
const static std::map< INT, std::string > | ENCODING_DICTIONARY |
![]() | |
const static std::map< std::string, INT > | COLOR_DICTIONARY |
Additional Inherited Members | |
![]() | |
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) |
ROS interface nodelet for UEye camera API from IDS Imaging Development Systems GMBH.
Definition at line 117 of file ueye_cam_nodelet.hpp.
ueye_cam::UEyeCamNodelet::UEyeCamNodelet | ( | ) |
Definition at line 76 of file ueye_cam_nodelet.cpp.
|
virtual |
Definition at line 129 of file ueye_cam_nodelet.cpp.
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.
|
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.
|
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.
|
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.
|
protected |
Main ROS interface "spin" loop.
Definition at line 1023 of file ueye_cam_nodelet.cpp.
|
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.
|
protected |
Returns image's timestamp or current wall time if driver call fails.
Definition at line 1296 of file ueye_cam_nodelet.cpp.
|
protectedvirtual |
Reimplemented from ueye_cam::UEyeCamDriver.
Definition at line 1330 of file ueye_cam_nodelet.cpp.
|
protected |
Loads the camera's intrinsic parameters from camIntrFilename.
Definition at line 1275 of file ueye_cam_nodelet.cpp.
|
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.
|
protected |
Loads, validates, and updates static ROS parameters.
Definition at line 220 of file ueye_cam_nodelet.cpp.
|
protected |
Reads parameter values from currently selected camera.
Definition at line 834 of file ueye_cam_nodelet.cpp.
|
protected |
Saves the camera's intrinsic parameters to camIntrFilename.
Definition at line 1287 of file ueye_cam_nodelet.cpp.
|
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.
|
protected |
Definition at line 1197 of file ueye_cam_nodelet.cpp.
|
protected |
Definition at line 1203 of file ueye_cam_nodelet.cpp.
|
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.
|
protected |
Definition at line 246 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 248 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 247 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 244 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 232 of file ueye_cam_nodelet.hpp.
|
static |
Definition at line 130 of file ueye_cam_nodelet.hpp.
|
static |
Definition at line 131 of file ueye_cam_nodelet.hpp.
|
static |
Definition at line 133 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 124 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 127 of file ueye_cam_nodelet.hpp.
|
static |
Definition at line 129 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 125 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 123 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 122 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 126 of file ueye_cam_nodelet.hpp.
|
static |
Definition at line 132 of file ueye_cam_nodelet.hpp.
|
staticprotected |
Definition at line 207 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 228 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 227 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 243 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 251 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 253 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 250 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 255 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 254 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 121 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 119 of file ueye_cam_nodelet.hpp.
|
staticconstexpr |
Definition at line 120 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 236 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 234 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 230 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 231 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 237 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 235 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 241 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 239 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 238 of file ueye_cam_nodelet.hpp.
|
protected |
Definition at line 245 of file ueye_cam_nodelet.hpp.