Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
libuvc_camera::CameraDriver Class Reference

#include <camera_driver.h>

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

libuvc_camera::CameraDriver::CameraDriver ( ros::NodeHandle  nh,
ros::NodeHandle  priv_nh 
)

Definition at line 48 of file camera_driver.cpp.

libuvc_camera::CameraDriver::~CameraDriver ( )

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 249 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 
)
staticprivate

Definition at line 291 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::CloseCamera ( )
private

Definition at line 450 of file camera_driver.cpp.

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

Definition at line 304 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 
)
staticprivate

Definition at line 243 of file camera_driver.cpp.

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

Definition at line 328 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.

bool libuvc_camera::CameraDriver::Start ( )

Definition at line 67 of file camera_driver.cpp.

void libuvc_camera::CameraDriver::Stop ( )

Definition at line 86 of file camera_driver.cpp.

Member Data Documentation

image_transport::CameraPublisher libuvc_camera::CameraDriver::cam_pub_
private

Definition at line 69 of file camera_driver.h.

camera_info_manager::CameraInfoManager libuvc_camera::CameraDriver::cinfo_manager_
private

Definition at line 75 of file camera_driver.h.

UVCCameraConfig libuvc_camera::CameraDriver::config_
private

Definition at line 72 of file camera_driver.h.

bool libuvc_camera::CameraDriver::config_changed_
private

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.

image_transport::ImageTransport libuvc_camera::CameraDriver::it_
private

Definition at line 68 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureClose = 3
staticprivate

Definition at line 32 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureRunning = 0
staticprivate

Definition at line 34 of file camera_driver.h.

const int libuvc_camera::CameraDriver::kReconfigureStop = 1
staticprivate

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.

ros::NodeHandle libuvc_camera::CameraDriver::nh_
private

Definition at line 58 of file camera_driver.h.

ros::NodeHandle libuvc_camera::CameraDriver::priv_nh_
private

Definition at line 58 of file camera_driver.h.

uvc_frame_t* libuvc_camera::CameraDriver::rgb_frame_
private

Definition at line 66 of file camera_driver.h.

State libuvc_camera::CameraDriver::state_
private

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 Mon Jul 8 2019 03:45:03