ROS camera abstraction. More...
#include <uvc_ros.h>
Definition at line 45 of file uvc_ros.cpp.
Definition at line 39 of file uvc_ros.cpp.
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] |
void V4RCamNode::publishCamera | ( | ) |
Definition at line 183 of file 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 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.
void V4RCamNode::showCameraImage | ( | ) |
Definition at line 254 of file 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] |
sensor_msgs::Image V4RCamNode::cameraImage_ [protected] |
sensor_msgs::CameraInfo V4RCamNode::cameraInfo_ [protected] |
sensor_msgs::Image V4RCamNode::cameraThumbnail_ [protected] |
int V4RCamNode::convert_image_ [protected] |
const int V4RCamNode::CONVERT_RAW = 0 [static] |
const int V4RCamNode::CONVERT_YUV422toBGR = 2 [static] |
const int V4RCamNode::CONVERT_YUV422toGray = 3 [static] |
const int V4RCamNode::CONVERT_YUV422toRGB = 1 [static] |
bool V4RCamNode::generate_dynamic_reconfigure_ [protected] |
ros::NodeHandle V4RCamNode::n_ [protected] |
ros::NodeHandle V4RCamNode::n_param_ [protected] |
bool V4RCamNode::queueRosParamToV4LCommit_ [protected] |
int V4RCamNode::ratioThumbnail_ [protected] |
ros::ServiceServer V4RCamNode::set_camera_info_srv_ [protected] |
bool V4RCamNode::show_camera_image_ [protected] |
boost::thread V4RCamNode::showCameraImageThread_ [protected] |
bool V4RCamNode::showCameraImageThreadActive_ [protected] |
ros::Subscriber V4RCamNode::subSphere_ [protected] |