camera_driver.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <libuvc/libuvc.h>
4 
5 #include <ros/ros.h>
8 #include <dynamic_reconfigure/server.h>
10 #include <boost/thread/mutex.hpp>
11 
12 #include <libuvc_camera/UVCCameraConfig.h>
13 
14 namespace libuvc_camera {
15 
16 class CameraDriver {
17 public:
19  ~CameraDriver();
20 
21  bool Start();
22  void Stop();
23 
24 private:
25  enum State {
26  kInitial = 0,
27  kStopped = 1,
28  kRunning = 2,
29  };
30 
31  // Flags controlling whether the sensor needs to be stopped (or reopened) when changing settings
32  static const int kReconfigureClose = 3; // Need to close and reopen sensor to change this setting
33  static const int kReconfigureStop = 1; // Need to stop the stream before changing this setting
34  static const int kReconfigureRunning = 0; // We can change this setting without stopping the stream
35 
36  void OpenCamera(UVCCameraConfig &new_config);
37  void CloseCamera();
38 
39  // Accept a reconfigure request from a client
40  void ReconfigureCallback(UVCCameraConfig &config, uint32_t level);
41  enum uvc_frame_format GetVideoMode(std::string vmode);
42  // Accept changes in values of automatically updated controls
43  void AutoControlsCallback(enum uvc_status_class status_class,
44  int event,
45  int selector,
46  enum uvc_status_attribute status_attribute,
47  void *data, size_t data_len);
48  static void AutoControlsCallbackAdapter(enum uvc_status_class status_class,
49  int event,
50  int selector,
51  enum uvc_status_attribute status_attribute,
52  void *data, size_t data_len,
53  void *ptr);
54  // Accept a new image frame from the camera
55  void ImageCallback(uvc_frame_t *frame);
56  static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr);
57 
59 
61  boost::recursive_mutex mutex_;
62 
63  uvc_context_t *ctx_;
64  uvc_device_t *dev_;
65  uvc_device_handle_t *devh_;
66  uvc_frame_t *rgb_frame_;
67 
70 
71  dynamic_reconfigure::Server<UVCCameraConfig> config_server_;
72  UVCCameraConfig config_;
74 
76 };
77 
78 };
libuvc_camera::CameraDriver::dev_
uvc_device_t * dev_
Definition: camera_driver.h:64
libuvc_camera::CameraDriver::kReconfigureRunning
static const int kReconfigureRunning
Definition: camera_driver.h:34
libuvc_camera::CameraDriver::config_server_
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
Definition: camera_driver.h:71
libuvc_camera
Definition: camera_driver.h:14
libuvc_camera::CameraDriver::CloseCamera
void CloseCamera()
Definition: camera_driver.cpp:462
image_transport::ImageTransport
libuvc_camera::CameraDriver::ImageCallbackAdapter
static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr)
Definition: camera_driver.cpp:253
libuvc_camera::CameraDriver::cam_pub_
image_transport::CameraPublisher cam_pub_
Definition: camera_driver.h:69
ros.h
camera_info_manager.h
libuvc_camera::CameraDriver::priv_nh_
ros::NodeHandle priv_nh_
Definition: camera_driver.h:58
libuvc_camera::CameraDriver::kInitial
@ kInitial
Definition: camera_driver.h:26
libuvc_camera::CameraDriver::nh_
ros::NodeHandle nh_
Definition: camera_driver.h:58
libuvc_camera::CameraDriver::rgb_frame_
uvc_frame_t * rgb_frame_
Definition: camera_driver.h:66
libuvc_camera::CameraDriver::State
State
Definition: camera_driver.h:25
libuvc_camera::CameraDriver::ReconfigureCallback
void ReconfigureCallback(UVCCameraConfig &config, uint32_t level)
Definition: camera_driver.cpp:102
libuvc_camera::CameraDriver::it_
image_transport::ImageTransport it_
Definition: camera_driver.h:68
libuvc_camera::CameraDriver::OpenCamera
void OpenCamera(UVCCameraConfig &new_config)
Definition: camera_driver.cpp:340
libuvc_camera::CameraDriver::state_
State state_
Definition: camera_driver.h:60
libuvc_camera::CameraDriver::config_
UVCCameraConfig config_
Definition: camera_driver.h:72
libuvc_camera::CameraDriver::AutoControlsCallbackAdapter
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)
Definition: camera_driver.cpp:301
libuvc_camera::CameraDriver::~CameraDriver
~CameraDriver()
Definition: camera_driver.cpp:59
libuvc_camera::CameraDriver::ImageCallback
void ImageCallback(uvc_frame_t *frame)
Definition: camera_driver.cpp:164
libuvc_camera::CameraDriver::kRunning
@ kRunning
Definition: camera_driver.h:28
camera_info_manager::CameraInfoManager
image_transport::CameraPublisher
libuvc_camera::CameraDriver::cinfo_manager_
camera_info_manager::CameraInfoManager cinfo_manager_
Definition: camera_driver.h:75
libuvc_camera::CameraDriver::kReconfigureStop
static const int kReconfigureStop
Definition: camera_driver.h:33
libuvc_camera::CameraDriver::AutoControlsCallback
void AutoControlsCallback(enum uvc_status_class status_class, int event, int selector, enum uvc_status_attribute status_attribute, void *data, size_t data_len)
Definition: camera_driver.cpp:259
image_transport.h
libuvc_camera::CameraDriver::Stop
void Stop()
Definition: camera_driver.cpp:86
libuvc_camera::CameraDriver::ctx_
uvc_context_t * ctx_
Definition: camera_driver.h:63
libuvc_camera::CameraDriver::mutex_
boost::recursive_mutex mutex_
Definition: camera_driver.h:61
libuvc_camera::CameraDriver::config_changed_
bool config_changed_
Definition: camera_driver.h:73
libuvc_camera::CameraDriver::kReconfigureClose
static const int kReconfigureClose
Definition: camera_driver.h:32
libuvc_camera::CameraDriver::kStopped
@ kStopped
Definition: camera_driver.h:27
libuvc_camera::CameraDriver::Start
bool Start()
Definition: camera_driver.cpp:67
libuvc_camera::CameraDriver
Definition: camera_driver.h:16
libuvc_camera::CameraDriver::devh_
uvc_device_handle_t * devh_
Definition: camera_driver.h:65
libuvc_camera::CameraDriver::GetVideoMode
enum uvc_frame_format GetVideoMode(std::string vmode)
Definition: camera_driver.cpp:314
ros::NodeHandle
camera_publisher.h
libuvc_camera::CameraDriver::CameraDriver
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
Definition: camera_driver.cpp:48


libuvc_camera
Author(s):
autogenerated on Wed Mar 2 2022 00:29:08