ROS camera abstraction. More...
#include <v4r_uvc_ros.h>

ROS camera abstraction.
Definition at line 33 of file v4r_uvc_ros.h.
Definition at line 45 of file v4r_uvc_ros.cpp.
Definition at line 39 of file v4r_uvc_ros.cpp.
| void V4RCamNode::callbackSphere | ( | const v4r_uvc::SphereConstPtr & | msg | ) |  [protected] | 
Definition at line 287 of file v4r_uvc_ros.cpp.
| void V4RCamNode::commitRosParamsToV4L | ( | bool | force = false | ) |  [protected] | 
Definition at line 62 of file v4r_uvc_ros.cpp.
| void V4RCamNode::commitV4LToRosParams | ( | ) |  [protected] | 
Definition at line 91 of file v4r_uvc_ros.cpp.
| void V4RCamNode::loopCamera | ( | ) |  [protected] | 
| void V4RCamNode::publishCamera | ( | ) | 
Definition at line 182 of file v4r_uvc_ros.cpp.
| void V4RCamNode::readCameraControls | ( | ) |  [protected] | 
reads and updates all local control values
| controls | control parameters | 
| void V4RCamNode::readControlEntryInfo | ( | ControlEntry * | entry | ) |  [protected] | 
reads a control entr
| entry | control entry | 
| void V4RCamNode::readInitParams | ( | ) |  [protected] | 
Definition at line 106 of file v4r_uvc_ros.cpp.
| void V4RCamNode::showCameraImage | ( | ) | 
Definition at line 253 of file v4r_uvc_ros.cpp.
| void V4RCamNode::updateControlEntry | ( | ControlEntry * | entry | ) |  [protected] | 
updates a control entr
| entry | control entry | 
| void V4RCamNode::updateDynamicReconfigureFile | ( | const char * | filename | ) | const  [protected] | 
generates a new reconfigure file
| void V4RCamNode::writeCameraControls | ( | ) |  [protected] | 
writes does parameter which are different to the current ones to the camera
| control | control parameters | 
| bool V4RCamNode::camera_freeze_  [protected] | 
Definition at line 57 of file v4r_uvc_ros.h.
| sensor_msgs::Image V4RCamNode::cameraImage_  [protected] | 
Definition at line 51 of file v4r_uvc_ros.h.
| sensor_msgs::CameraInfo V4RCamNode::cameraInfo_  [protected] | 
Definition at line 50 of file v4r_uvc_ros.h.
Definition at line 48 of file v4r_uvc_ros.h.
| sensor_msgs::Image V4RCamNode::cameraThumbnail_  [protected] | 
Definition at line 52 of file v4r_uvc_ros.h.
Definition at line 49 of file v4r_uvc_ros.h.
| int V4RCamNode::convert_image_  [protected] | 
Definition at line 66 of file v4r_uvc_ros.h.
| const int V4RCamNode::CONVERT_RAW = 0  [static] | 
Definition at line 35 of file v4r_uvc_ros.h.
| const int V4RCamNode::CONVERT_YUV422toBGR = 2  [static] | 
Definition at line 37 of file v4r_uvc_ros.h.
| const int V4RCamNode::CONVERT_YUV422toGray = 3  [static] | 
Definition at line 38 of file v4r_uvc_ros.h.
| const int V4RCamNode::CONVERT_YUV422toRGB = 1  [static] | 
Definition at line 36 of file v4r_uvc_ros.h.
| bool V4RCamNode::generate_dynamic_reconfigure_  [protected] | 
Definition at line 55 of file v4r_uvc_ros.h.
Definition at line 47 of file v4r_uvc_ros.h.
| ros::NodeHandle V4RCamNode::n_  [protected] | 
Definition at line 45 of file v4r_uvc_ros.h.
| ros::NodeHandle V4RCamNode::n_param_  [protected] | 
Definition at line 46 of file v4r_uvc_ros.h.
| bool V4RCamNode::queueRosParamToV4LCommit_  [protected] | 
Definition at line 58 of file v4r_uvc_ros.h.
| int V4RCamNode::ratioThumbnail_  [protected] | 
Definition at line 67 of file v4r_uvc_ros.h.
| bool V4RCamNode::show_camera_image_  [protected] | 
Definition at line 56 of file v4r_uvc_ros.h.
| boost::thread V4RCamNode::showCameraImageThread_  [protected] | 
Definition at line 60 of file v4r_uvc_ros.h.
| bool V4RCamNode::showCameraImageThreadActive_  [protected] | 
Definition at line 59 of file v4r_uvc_ros.h.
| ros::Subscriber V4RCamNode::subSphere_  [protected] | 
Definition at line 53 of file v4r_uvc_ros.h.