Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
libuvc_camera::CameraDriver Class Reference

#include <camera_driver.h>

List of all members.

Public Member Functions

 CameraDriver (ros::NodeHandle nh, ros::NodeHandle priv_nh)
bool Start ()
void Stop ()
 ~CameraDriver ()

Private Types

enum  State { kInitial = 0, kStopped = 1, kRunning = 2 }

Private Member Functions

void AutoControlsCallback (enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len)
void CloseCamera ()
enum uvc_frame_format GetVideoMode (std::string vmode)
void ImageCallback (uvc_frame_t *frame)
void OpenCamera (UVCCameraConfig &new_config)
void ReconfigureCallback (UVCCameraConfig &config, uint32_t level)

Static Private Member Functions

static void AutoControlsCallbackAdapter (enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len, void *ptr)
static void ImageCallbackAdapter (uvc_frame_t *frame, void *ptr)

Private Attributes

image_transport::CameraPublisher cam_pub_
camera_info_manager::CameraInfoManager cinfo_manager_
UVCCameraConfig config_
bool config_changed_
dynamic_reconfigure::Server
< UVCCameraConfig > 
config_server_
uvc_context_t * ctx_
uvc_device_t * dev_
uvc_device_handle_t * devh_
image_transport::ImageTransport it_
boost::recursive_mutex mutex_
ros::NodeHandle nh_
ros::NodeHandle priv_nh_
uvc_frame_t * rgb_frame_
State state_

Static Private Attributes

static const int kReconfigureClose = 3
static const int kReconfigureRunning = 0
static const int kReconfigureStop = 1

Detailed Description

Definition at line 16 of file camera_driver.h.


Member Enumeration Documentation

Enumerator:
kInitial 
kStopped 
kRunning 

Definition at line 25 of file camera_driver.h.


Constructor & Destructor Documentation

Definition at line 48 of file camera_driver.cpp.

Definition at line 59 of file camera_driver.cpp.


Member Function Documentation

void libuvc_camera::CameraDriver::AutoControlsCallback ( enum uvc_status_class  status_class,
int  event,
int  selector,
enum uvc_status_attribute  status_attribute,
void *  data,
size_t  data_len 
) [private]

Definition at line 259 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::AutoControlsCallbackAdapter ( enum uvc_status_class  status_class,
int  event,
int  selector,
enum uvc_status_attribute  status_attribute,
void *  data,
size_t  data_len,
void *  ptr 
) [static, private]

Definition at line 301 of file camera_driver.cpp.

Definition at line 462 of file camera_driver.cpp.

enum uvc_frame_format libuvc_camera::CameraDriver::GetVideoMode ( std::string  vmode) [private]

Definition at line 314 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::ImageCallback ( uvc_frame_t *  frame) [private]

Definition at line 164 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::ImageCallbackAdapter ( uvc_frame_t *  frame,
void *  ptr 
) [static, private]

Definition at line 253 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::OpenCamera ( UVCCameraConfig &  new_config) [private]

Definition at line 340 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::ReconfigureCallback ( UVCCameraConfig &  config,
uint32_t  level 
) [private]

Definition at line 102 of file camera_driver.cpp.

Definition at line 67 of file camera_driver.cpp.

Definition at line 86 of file camera_driver.cpp.


Member Data Documentation

Definition at line 69 of file camera_driver.h.

Definition at line 75 of file camera_driver.h.

UVCCameraConfig libuvc_camera::CameraDriver::config_ [private]

Definition at line 72 of file camera_driver.h.

Definition at line 73 of file camera_driver.h.

dynamic_reconfigure::Server<UVCCameraConfig> libuvc_camera::CameraDriver::config_server_ [private]

Definition at line 71 of file camera_driver.h.

uvc_context_t* libuvc_camera::CameraDriver::ctx_ [private]

Definition at line 63 of file camera_driver.h.

uvc_device_t* libuvc_camera::CameraDriver::dev_ [private]

Definition at line 64 of file camera_driver.h.

uvc_device_handle_t* libuvc_camera::CameraDriver::devh_ [private]

Definition at line 65 of file camera_driver.h.

Definition at line 68 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureClose = 3 [static, private]

Definition at line 32 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureRunning = 0 [static, private]

Definition at line 34 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureStop = 1 [static, private]

Definition at line 33 of file camera_driver.h.

boost::recursive_mutex libuvc_camera::CameraDriver::mutex_ [private]

Definition at line 61 of file camera_driver.h.

Definition at line 58 of file camera_driver.h.

Definition at line 58 of file camera_driver.h.

Definition at line 66 of file camera_driver.h.

Definition at line 60 of file camera_driver.h.


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


libuvc_camera
Author(s):
autogenerated on Tue Jul 9 2019 03:20:57