3 #include <libuvc/libuvc.h> 8 #include <dynamic_reconfigure/server.h> 10 #include <boost/thread/mutex.hpp> 12 #include <libuvc_camera/UVCCameraConfig.h> 46 enum uvc_status_attribute status_attribute,
47 void *data,
size_t data_len);
51 enum uvc_status_attribute status_attribute,
52 void *data,
size_t data_len,
boost::recursive_mutex mutex_
static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr)
enum uvc_frame_format GetVideoMode(std::string vmode)
static const int kReconfigureRunning
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 const int kReconfigureStop
image_transport::ImageTransport it_
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
void ReconfigureCallback(UVCCameraConfig &config, uint32_t level)
void ImageCallback(uvc_frame_t *frame)
void OpenCamera(UVCCameraConfig &new_config)
image_transport::CameraPublisher cam_pub_
camera_info_manager::CameraInfoManager cinfo_manager_
void AutoControlsCallback(enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len)
static const int kReconfigureClose
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
uvc_device_handle_t * devh_