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

#include <ueye_cam_nodelet.hpp>

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

List of all members.

Public Member Functions

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

Static Public Attributes

static const std::string DEFAULT_CAMERA_NAME = "camera"
static const std::string DEFAULT_CAMERA_TOPIC = "image_raw"
static const std::string DEFAULT_COLOR_MODE = ""
static constexpr double DEFAULT_EXPOSURE = 33.0
static constexpr int DEFAULT_FLASH_DURATION = 1000
static const std::string DEFAULT_FRAME_NAME = "camera"
static constexpr double DEFAULT_FRAME_RATE = 10.0
static constexpr int DEFAULT_IMAGE_HEIGHT = 480
static constexpr int DEFAULT_IMAGE_WIDTH = 640
static constexpr int DEFAULT_PIXEL_CLOCK = 25
static constexpr unsigned int RECONFIGURE_CLOSE = 3
static constexpr unsigned int RECONFIGURE_RUNNING = 0
static constexpr unsigned int RECONFIGURE_STOP = 1

Protected Member Functions

virtual INT connectCam ()
virtual INT disconnectCam ()
void frameGrabLoop ()
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 ()

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

Detailed Description

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

Definition at line 72 of file ueye_cam_nodelet.hpp.


Constructor & Destructor Documentation

Definition at line 73 of file ueye_cam_nodelet.cpp.

Definition at line 113 of file ueye_cam_nodelet.cpp.


Member Function Documentation

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

Handles callbacks from dynamic_reconfigure.

Definition at line 494 of file ueye_cam_nodelet.cpp.

INT ueye_cam::UEyeCamNodelet::connectCam ( ) [protected, virtual]

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 855 of file ueye_cam_nodelet.cpp.

INT ueye_cam::UEyeCamNodelet::disconnectCam ( ) [protected, virtual]

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

Reimplemented from ueye_cam::UEyeCamDriver.

Definition at line 876 of file ueye_cam_nodelet.cpp.

Main ROS interface "spin" loop.

Definition at line 898 of file ueye_cam_nodelet.cpp.

Loads the camera's intrinsic parameters from camIntrFilename.

Definition at line 1059 of file ueye_cam_nodelet.cpp.

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

Implements nodelet::Nodelet.

Definition at line 126 of file ueye_cam_nodelet.cpp.

Loads, validates, and updates static ROS parameters.

Definition at line 196 of file ueye_cam_nodelet.cpp.

Reads parameter values from currently selected camera.

Definition at line 638 of file ueye_cam_nodelet.cpp.

Saves the camera's intrinsic parameters to camIntrFilename.

Definition at line 1071 of file ueye_cam_nodelet.cpp.

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 888 of file ueye_cam_nodelet.cpp.

Definition at line 1044 of file ueye_cam_nodelet.cpp.

Definition at line 1050 of file ueye_cam_nodelet.cpp.


Member Data Documentation

Definition at line 171 of file ueye_cam_nodelet.hpp.

ueye_cam::UEyeCamConfig ueye_cam::UEyeCamNodelet::cam_params_ [protected]

Definition at line 173 of file ueye_cam_nodelet.hpp.

Definition at line 172 of file ueye_cam_nodelet.hpp.

std::string ueye_cam::UEyeCamNodelet::cam_topic_ [protected]

Definition at line 170 of file ueye_cam_nodelet.hpp.

Definition at line 160 of file ueye_cam_nodelet.hpp.

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

Definition at line 85 of file ueye_cam_nodelet.hpp.

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

Definition at line 86 of file ueye_cam_nodelet.hpp.

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

Definition at line 87 of file ueye_cam_nodelet.hpp.

constexpr double ueye_cam::UEyeCamNodelet::DEFAULT_EXPOSURE = 33.0 [static]

Definition at line 79 of file ueye_cam_nodelet.hpp.

constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_FLASH_DURATION = 1000 [static]

Definition at line 82 of file ueye_cam_nodelet.hpp.

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

Definition at line 84 of file ueye_cam_nodelet.hpp.

constexpr double ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_RATE = 10.0 [static]

Definition at line 80 of file ueye_cam_nodelet.hpp.

constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_HEIGHT = 480 [static]

Definition at line 78 of file ueye_cam_nodelet.hpp.

constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_WIDTH = 640 [static]

Definition at line 77 of file ueye_cam_nodelet.hpp.

constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_PIXEL_CLOCK = 25 [static]

Definition at line 81 of file ueye_cam_nodelet.hpp.

Definition at line 156 of file ueye_cam_nodelet.hpp.

Definition at line 155 of file ueye_cam_nodelet.hpp.

std::string ueye_cam::UEyeCamNodelet::frame_name_ [protected]

Definition at line 169 of file ueye_cam_nodelet.hpp.

constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_CLOSE = 3 [static]

Definition at line 76 of file ueye_cam_nodelet.hpp.

constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_RUNNING = 0 [static]

Definition at line 74 of file ueye_cam_nodelet.hpp.

constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_STOP = 1 [static]

Definition at line 75 of file ueye_cam_nodelet.hpp.

sensor_msgs::CameraInfo ueye_cam::UEyeCamNodelet::ros_cam_info_ [protected]

Definition at line 164 of file ueye_cam_nodelet.hpp.

Definition at line 162 of file ueye_cam_nodelet.hpp.

Definition at line 158 of file ueye_cam_nodelet.hpp.

boost::recursive_mutex ueye_cam::UEyeCamNodelet::ros_cfg_mutex_ [protected]

Definition at line 159 of file ueye_cam_nodelet.hpp.

Definition at line 165 of file ueye_cam_nodelet.hpp.

sensor_msgs::Image ueye_cam::UEyeCamNodelet::ros_image_ [protected]

Definition at line 163 of file ueye_cam_nodelet.hpp.

Definition at line 167 of file ueye_cam_nodelet.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