ROS camera abstraction. More...
#include <uvc_ros.h>
Public Member Functions | |
void | publishCamera () |
void | showCameraImage () |
V4RCamNode (ros::NodeHandle &n) | |
~V4RCamNode () | |
Public Member Functions inherited from V4RCam | |
const std::vector< ControlEntryPtr > & | detectControlEnties () |
ControlEntryPtr | getControlEntry (std::string varName) |
bool | grab () |
destructor More... | |
bool | hasErrorMsg () const |
bool | hasInfoMsg () const |
FD | initCamera (const std::string &videoDevice="") |
vector of the current supported control entries More... | |
bool | isBlackListed (int control) |
int | load_controls (const std::string &filename) |
std::string | pullErrorMsg () |
std::string | pullInfoMsg () |
int | save_controls (const std::string &filename) |
int | v4lget (ControlEntryPtr entry) |
int | v4lgetInfo (ControlEntryPtr entry) |
v4lcontrols More... | |
int | v4lset (ControlEntryPtr entry) |
int | v4lupdate (ControlEntryPtr entry) |
V4RCam () | |
shared pointer for ControlEntry More... | |
~V4RCam () | |
construtor More... | |
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 |
Static Public Attributes inherited from V4RCam | |
static const int | ERROR = 1 |
static const int | LOAD = 1 |
static const int | NA = 0 |
static const int | OK = 0 |
static const int | SAVE = 2 |
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 () |
Additional Inherited Members | |
Public Types inherited from V4RCam | |
typedef boost::shared_ptr< ControlEntry > | ControlEntryPtr |
typedef int | FD |
typedef boost::shared_ptr< v4l2_control > | v4l2_controlPtr |
Static Public Member Functions inherited from V4RCam | |
static char | removeNonAlNum (char in) |
V4RCamNode::V4RCamNode | ( | ros::NodeHandle & | n | ) |
Definition at line 45 of file uvc_ros.cpp.
V4RCamNode::~V4RCamNode | ( | ) |
Definition at line 39 of file uvc_ros.cpp.
|
protected |
Definition at line 290 of file uvc_ros.cpp.
|
protected |
Definition at line 63 of file uvc_ros.cpp.
|
protected |
Definition at line 92 of file uvc_ros.cpp.
|
protected |
void V4RCamNode::publishCamera | ( | ) |
Definition at line 183 of file uvc_ros.cpp.
|
protected |
reads and updates all local control values
controls | control parameters |
|
protected |
reads a control entr
entry | control entry |
|
protected |
Definition at line 107 of file uvc_ros.cpp.
|
protected |
Definition at line 297 of file uvc_ros.cpp.
void V4RCamNode::showCameraImage | ( | ) |
Definition at line 254 of file uvc_ros.cpp.
|
protected |
updates a control entr
entry | control entry |
|
protected |
generates a new reconfigure file
|
protected |
writes does parameter which are different to the current ones to the camera
control | control parameters |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |