camera_driver.h
Go to the documentation of this file.
00001 #pragma once
00002 
00003 #include <libuvc/libuvc.h>
00004 
00005 #include <ros/ros.h>
00006 #include <image_transport/image_transport.h>
00007 #include <image_transport/camera_publisher.h>
00008 #include <dynamic_reconfigure/server.h>
00009 #include <camera_info_manager/camera_info_manager.h>
00010 #include <boost/thread/mutex.hpp>
00011 
00012 #include <libuvc_camera/UVCCameraConfig.h>
00013 
00014 namespace libuvc_camera {
00015 
00016 class CameraDriver {
00017 public:
00018   CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh);
00019   ~CameraDriver();
00020 
00021   bool Start();
00022   void Stop();
00023 
00024 private:
00025   enum State {
00026     kInitial = 0,
00027     kStopped = 1,
00028     kRunning = 2,
00029   };
00030 
00031   // Flags controlling whether the sensor needs to be stopped (or reopened) when changing settings
00032   static const int kReconfigureClose = 3; // Need to close and reopen sensor to change this setting
00033   static const int kReconfigureStop = 1; // Need to stop the stream before changing this setting
00034   static const int kReconfigureRunning = 0; // We can change this setting without stopping the stream
00035 
00036   void OpenCamera(UVCCameraConfig &new_config);
00037   void CloseCamera();
00038 
00039   // Accept a reconfigure request from a client
00040   void ReconfigureCallback(UVCCameraConfig &config, uint32_t level);
00041   enum uvc_frame_format GetVideoMode(std::string vmode);
00042   // Accept changes in values of automatically updated controls
00043   void AutoControlsCallback(enum uvc_status_class status_class,
00044                             int event,
00045                             int selector,
00046                             enum uvc_status_attribute status_attribute,
00047                             void *data, size_t data_len);
00048   static void AutoControlsCallbackAdapter(enum uvc_status_class status_class,
00049                                           int event,
00050                                           int selector,
00051                                           enum uvc_status_attribute status_attribute,
00052                                           void *data, size_t data_len,
00053                                           void *ptr);
00054   // Accept a new image frame from the camera
00055   void ImageCallback(uvc_frame_t *frame);
00056   static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr);
00057 
00058   ros::NodeHandle nh_, priv_nh_;
00059 
00060   State state_;
00061   boost::recursive_mutex mutex_;
00062 
00063   uvc_context_t *ctx_;
00064   uvc_device_t *dev_;
00065   uvc_device_handle_t *devh_;
00066   uvc_frame_t *rgb_frame_;
00067 
00068   image_transport::ImageTransport it_;
00069   image_transport::CameraPublisher cam_pub_;
00070 
00071   dynamic_reconfigure::Server<UVCCameraConfig> config_server_;
00072   UVCCameraConfig config_;
00073   bool config_changed_;
00074 
00075   camera_info_manager::CameraInfoManager cinfo_manager_;
00076 };
00077 
00078 };


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