Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
V4RCamNode Class Reference

ROS camera abstraction. More...

#include <uvc_ros.h>

Inheritance diagram for V4RCamNode:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void publishCamera ()
void showCameraImage ()
 V4RCamNode (ros::NodeHandle &n)
 ~V4RCamNode ()

Static Public Attributes

static const int CONVERT_RAW = 0
static const int CONVERT_YUV422toBGR = 2
static const int CONVERT_YUV422toGray = 3
static const int CONVERT_YUV422toRGB = 1

Protected Member Functions

void callbackSphere (const tuw_uvc::SphereConstPtr &msg)
void commitRosParamsToV4L (bool force=false)
void commitV4LToRosParams ()
void loopCamera ()
void readCameraControls ()
void readControlEntryInfo (ControlEntry *entry)
void readInitParams ()
bool setCameraInfo (sensor_msgs::SetCameraInfoRequest &req, sensor_msgs::SetCameraInfoResponse &rsp)
void updateControlEntry (ControlEntry *entry)
void updateDynamicReconfigureFile (const char *filename) const
void writeCameraControls ()

Protected Attributes

bool camera_freeze_
sensor_msgs::Image cameraImage_
sensor_msgs::CameraInfo cameraInfo_
image_transport::CameraPublisher cameraPublisher_
sensor_msgs::Image cameraThumbnail_
image_transport::Publisher cameraThumbnailPublisher_
int convert_image_
bool generate_dynamic_reconfigure_
image_transport::ImageTransport imageTransport_
ros::NodeHandle n_
ros::NodeHandle n_param_
bool queueRosParamToV4LCommit_
int ratioThumbnail_
ros::ServiceServer set_camera_info_srv_
bool show_camera_image_
boost::thread showCameraImageThread_
bool showCameraImageThreadActive_
ros::Subscriber subSphere_

Detailed Description

ROS camera abstraction.

Definition at line 34 of file uvc_ros.h.


Constructor & Destructor Documentation

Definition at line 45 of file uvc_ros.cpp.

Definition at line 39 of file uvc_ros.cpp.


Member Function Documentation

void V4RCamNode::callbackSphere ( const tuw_uvc::SphereConstPtr &  msg) [protected]

Definition at line 290 of file uvc_ros.cpp.

void V4RCamNode::commitRosParamsToV4L ( bool  force = false) [protected]

Definition at line 63 of file uvc_ros.cpp.

void V4RCamNode::commitV4LToRosParams ( ) [protected]

Definition at line 92 of file uvc_ros.cpp.

void V4RCamNode::loopCamera ( ) [protected]

Definition at line 183 of file uvc_ros.cpp.

void V4RCamNode::readCameraControls ( ) [protected]

reads and updates all local control values

Parameters:
controlscontrol parameters
void V4RCamNode::readControlEntryInfo ( ControlEntry entry) [protected]

reads a control entr

Parameters:
entrycontrol entry
void V4RCamNode::readInitParams ( ) [protected]

Definition at line 107 of file uvc_ros.cpp.

bool V4RCamNode::setCameraInfo ( sensor_msgs::SetCameraInfoRequest &  req,
sensor_msgs::SetCameraInfoResponse &  rsp 
) [protected]

Definition at line 297 of file uvc_ros.cpp.

Definition at line 254 of file uvc_ros.cpp.

void V4RCamNode::updateControlEntry ( ControlEntry entry) [protected]

updates a control entr

Parameters:
entrycontrol 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

Parameters:
controlcontrol parameters

Member Data Documentation

bool V4RCamNode::camera_freeze_ [protected]

Definition at line 60 of file uvc_ros.h.

sensor_msgs::Image V4RCamNode::cameraImage_ [protected]

Definition at line 52 of file uvc_ros.h.

sensor_msgs::CameraInfo V4RCamNode::cameraInfo_ [protected]

Definition at line 51 of file uvc_ros.h.

Definition at line 49 of file uvc_ros.h.

sensor_msgs::Image V4RCamNode::cameraThumbnail_ [protected]

Definition at line 53 of file uvc_ros.h.

Definition at line 50 of file uvc_ros.h.

int V4RCamNode::convert_image_ [protected]

Definition at line 69 of file uvc_ros.h.

const int V4RCamNode::CONVERT_RAW = 0 [static]

Definition at line 36 of file uvc_ros.h.

const int V4RCamNode::CONVERT_YUV422toBGR = 2 [static]

Definition at line 38 of file uvc_ros.h.

const int V4RCamNode::CONVERT_YUV422toGray = 3 [static]

Definition at line 39 of file uvc_ros.h.

const int V4RCamNode::CONVERT_YUV422toRGB = 1 [static]

Definition at line 37 of file uvc_ros.h.

Definition at line 58 of file uvc_ros.h.

Definition at line 48 of file uvc_ros.h.

Definition at line 46 of file uvc_ros.h.

Definition at line 47 of file uvc_ros.h.

Definition at line 61 of file uvc_ros.h.

int V4RCamNode::ratioThumbnail_ [protected]

Definition at line 70 of file uvc_ros.h.

Definition at line 54 of file uvc_ros.h.

Definition at line 59 of file uvc_ros.h.

boost::thread V4RCamNode::showCameraImageThread_ [protected]

Definition at line 63 of file uvc_ros.h.

Definition at line 62 of file uvc_ros.h.

Definition at line 55 of file uvc_ros.h.


The documentation for this class was generated from the following files:


tuw_uvc
Author(s):
autogenerated on Sun May 29 2016 02:50:28