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 #include <sensor_msgs/CameraInfo.h>
12 #include <astra_camera/GetUVCExposure.h>
13 #include <astra_camera/SetUVCExposure.h>
14 #include <astra_camera/GetUVCGain.h>
15 #include <astra_camera/SetUVCGain.h>
16 #include <astra_camera/GetUVCWhiteBalance.h>
17 #include <astra_camera/SetUVCWhiteBalance.h>
19 #include <astra_camera/UVCCameraConfig.h>
20 
21 #include <string>
22 
23 namespace libuvc_camera {
24 
25 class CameraDriver {
26 public:
28  ~CameraDriver();
29 
30  bool Start();
31  void Stop();
32 
33 private:
34  enum State {
35  kInitial = 0,
36  kStopped = 1,
37  kRunning = 2,
38  };
39 
40  // Flags controlling whether the sensor needs to be stopped (or reopened) when changing settings
41  static const int kReconfigureClose = 3; // Need to close and reopen sensor to change this setting
42  static const int kReconfigureStop = 1; // Need to stop the stream before changing this setting
43  static const int kReconfigureRunning = 0; // We can change this setting without stopping the stream
44 
45  void OpenCamera(UVCCameraConfig &new_config);
46  void CloseCamera();
47 
48  // Accept a reconfigure request from a client
49  void ReconfigureCallback(UVCCameraConfig &config, uint32_t level);
50  enum uvc_frame_format GetVideoMode(std::string vmode);
51  // Accept changes in values of automatically updated controls
52  void AutoControlsCallback(enum uvc_status_class status_class,
53  int event,
54  int selector,
55  enum uvc_status_attribute status_attribute,
56  void *data, size_t data_len);
57  static void AutoControlsCallbackAdapter(enum uvc_status_class status_class,
58  int event,
59  int selector,
60  enum uvc_status_attribute status_attribute,
61  void *data, size_t data_len,
62  void *ptr);
63  // Accept a new image frame from the camera
64  void ImageCallback(uvc_frame_t *frame);
65  static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr);
66  bool getUVCExposureCb(astra_camera::GetUVCExposureRequest& req, astra_camera::GetUVCExposureResponse& res);
67  bool setUVCExposureCb(astra_camera::SetUVCExposureRequest& req, astra_camera::SetUVCExposureResponse& res);
68  bool getUVCGainCb(astra_camera::GetUVCGainRequest& req, astra_camera::GetUVCGainResponse& res);
69  bool setUVCGainCb(astra_camera::SetUVCGainRequest& req, astra_camera::SetUVCGainResponse& res);
70  bool getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest& req, astra_camera::GetUVCWhiteBalanceResponse& res);
71  bool setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest& req, astra_camera::SetUVCWhiteBalanceResponse& res);
72 
74 
76  boost::recursive_mutex mutex_;
77 
78  uvc_context_t *ctx_;
79  uvc_device_t *dev_;
80  uvc_device_handle_t *devh_;
81  uvc_frame_t *rgb_frame_;
82 
85 
86  dynamic_reconfigure::Server<UVCCameraConfig> config_server_;
87  UVCCameraConfig config_;
89 
92  std::string ns;
93  std::string ns_no_slash;
94 
101 
104 
107  std::string device_type_;
108  sensor_msgs::CameraInfo camera_info_;
112 };
113 
114 };
libuvc_camera::CameraDriver::dev_
uvc_device_t * dev_
Definition: camera_driver.h:79
libuvc_camera::CameraDriver::device_type_client
ros::ServiceClient device_type_client
Definition: camera_driver.h:102
libuvc_camera::CameraDriver::kReconfigureRunning
static const int kReconfigureRunning
Definition: camera_driver.h:43
libuvc_camera::CameraDriver::config_server_
dynamic_reconfigure::Server< UVCCameraConfig > config_server_
Definition: camera_driver.h:86
libuvc_camera::CameraDriver::getUVCExposureCb
bool getUVCExposureCb(astra_camera::GetUVCExposureRequest &req, astra_camera::GetUVCExposureResponse &res)
Definition: camera_driver.cpp:95
libuvc_camera
Definition: camera_driver.h:23
libuvc_camera::CameraDriver::CloseCamera
void CloseCamera()
Definition: camera_driver.cpp:609
image_transport::ImageTransport
libuvc_camera::CameraDriver::ImageCallbackAdapter
static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr)
Definition: camera_driver.cpp:402
libuvc_camera::CameraDriver::cam_pub_
image_transport::CameraPublisher cam_pub_
Definition: camera_driver.h:84
ros.h
libuvc_camera::CameraDriver::device_type_init_
bool device_type_init_
Definition: camera_driver.h:105
libuvc_camera::CameraDriver::ns
std::string ns
Definition: camera_driver.h:92
camera_info_manager.h
libuvc_camera::CameraDriver::priv_nh_
ros::NodeHandle priv_nh_
Definition: camera_driver.h:73
libuvc_camera::CameraDriver::kInitial
@ kInitial
Definition: camera_driver.h:35
libuvc_camera::CameraDriver::nh_
ros::NodeHandle nh_
Definition: camera_driver.h:73
libuvc_camera::CameraDriver::rgb_frame_
uvc_frame_t * rgb_frame_
Definition: camera_driver.h:81
libuvc_camera::CameraDriver::ns_no_slash
std::string ns_no_slash
Definition: camera_driver.h:93
libuvc_camera::CameraDriver::get_uvc_exposure_server
ros::ServiceServer get_uvc_exposure_server
Definition: camera_driver.h:95
libuvc_camera::CameraDriver::State
State
Definition: camera_driver.h:34
libuvc_camera::CameraDriver::ReconfigureCallback
void ReconfigureCallback(UVCCameraConfig &config, uint32_t level)
Definition: camera_driver.cpp:189
libuvc_camera::CameraDriver::getUVCWhiteBalanceCb
bool getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest &req, astra_camera::GetUVCWhiteBalanceResponse &res)
Definition: camera_driver.cpp:134
libuvc_camera::CameraDriver::camera_info_init_
bool camera_info_init_
Definition: camera_driver.h:106
libuvc_camera::CameraDriver::it_
image_transport::ImageTransport it_
Definition: camera_driver.h:83
ros::ServiceServer
libuvc_camera::CameraDriver::OpenCamera
void OpenCamera(UVCCameraConfig &new_config)
Definition: camera_driver.cpp:487
libuvc_camera::CameraDriver::get_uvc_gain_server
ros::ServiceServer get_uvc_gain_server
Definition: camera_driver.h:97
libuvc_camera::CameraDriver::set_uvc_gain_server
ros::ServiceServer set_uvc_gain_server
Definition: camera_driver.h:98
libuvc_camera::CameraDriver::setUVCExposureCb
bool setUVCExposureCb(astra_camera::SetUVCExposureRequest &req, astra_camera::SetUVCExposureResponse &res)
Definition: camera_driver.cpp:103
libuvc_camera::CameraDriver::state_
State state_
Definition: camera_driver.h:75
libuvc_camera::CameraDriver::setUVCWhiteBalanceCb
bool setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest &req, astra_camera::SetUVCWhiteBalanceResponse &res)
Definition: camera_driver.cpp:142
libuvc_camera::CameraDriver::config_
UVCCameraConfig config_
Definition: camera_driver.h:87
astra_device_type.h
libuvc_camera::CameraDriver::camera_info_
sensor_msgs::CameraInfo camera_info_
Definition: camera_driver.h:108
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:450
libuvc_camera::CameraDriver::~CameraDriver
~CameraDriver()
Definition: camera_driver.cpp:87
libuvc_camera::CameraDriver::ImageCallback
void ImageCallback(uvc_frame_t *frame)
Definition: camera_driver.cpp:251
libuvc_camera::CameraDriver::kRunning
@ kRunning
Definition: camera_driver.h:37
ros::ServiceClient
camera_info_manager::CameraInfoManager
image_transport::CameraPublisher
libuvc_camera::CameraDriver::uvc_flip_
int uvc_flip_
Definition: camera_driver.h:109
libuvc_camera::CameraDriver::cinfo_manager_
camera_info_manager::CameraInfoManager cinfo_manager_
Definition: camera_driver.h:90
libuvc_camera::CameraDriver::camera_info_client
ros::ServiceClient camera_info_client
Definition: camera_driver.h:103
libuvc_camera::CameraDriver::set_uvc_white_balance_server
ros::ServiceServer set_uvc_white_balance_server
Definition: camera_driver.h:100
libuvc_camera::CameraDriver::kReconfigureStop
static const int kReconfigureStop
Definition: camera_driver.h:42
libuvc_camera::CameraDriver::setUVCGainCb
bool setUVCGainCb(astra_camera::SetUVCGainRequest &req, astra_camera::SetUVCGainResponse &res)
Definition: camera_driver.cpp:128
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:408
libuvc_camera::CameraDriver::param_init_
bool param_init_
Definition: camera_driver.h:91
image_transport.h
libuvc_camera::CameraDriver::set_uvc_exposure_server
ros::ServiceServer set_uvc_exposure_server
Definition: camera_driver.h:96
libuvc_camera::CameraDriver::getUVCGainCb
bool getUVCGainCb(astra_camera::GetUVCGainRequest &req, astra_camera::GetUVCGainResponse &res)
Definition: camera_driver.cpp:120
OB_DEVICE_NO
OB_DEVICE_NO
Definition: astra_device_type.h:9
libuvc_camera::CameraDriver::Stop
void Stop()
Definition: camera_driver.cpp:173
libuvc_camera::CameraDriver::ctx_
uvc_context_t * ctx_
Definition: camera_driver.h:78
libuvc_camera::CameraDriver::mutex_
boost::recursive_mutex mutex_
Definition: camera_driver.h:76
libuvc_camera::CameraDriver::config_changed_
bool config_changed_
Definition: camera_driver.h:88
libuvc_camera::CameraDriver::kReconfigureClose
static const int kReconfigureClose
Definition: camera_driver.h:41
libuvc_camera::CameraDriver::kStopped
@ kStopped
Definition: camera_driver.h:36
uint32_t
unsigned int uint32_t
Definition: OniPlatformWin32.h:67
libuvc_camera::CameraDriver::Start
bool Start()
Definition: camera_driver.cpp:154
libuvc_camera::CameraDriver
Definition: camera_driver.h:25
libuvc_camera::CameraDriver::device_type_
std::string device_type_
Definition: camera_driver.h:107
libuvc_camera::CameraDriver::device_type_no_
OB_DEVICE_NO device_type_no_
Definition: camera_driver.h:110
libuvc_camera::CameraDriver::devh_
uvc_device_handle_t * devh_
Definition: camera_driver.h:80
libuvc_camera::CameraDriver::GetVideoMode
enum uvc_frame_format GetVideoMode(std::string vmode)
Definition: camera_driver.cpp:463
ros::NodeHandle
camera_publisher.h
libuvc_camera::CameraDriver::get_uvc_white_balance_server
ros::ServiceServer get_uvc_white_balance_server
Definition: camera_driver.h:99
libuvc_camera::CameraDriver::CameraDriver
CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh)
Definition: camera_driver.cpp:52
libuvc_camera::CameraDriver::camera_info_valid_
bool camera_info_valid_
Definition: camera_driver.h:111


ros_astra_camera
Author(s): Tim Liu
autogenerated on Wed Mar 2 2022 00:52:57