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 #include <sensor_msgs/CameraInfo.h>
00012 #include <astra_camera/GetUVCExposure.h>
00013 #include <astra_camera/SetUVCExposure.h>
00014 #include <astra_camera/GetUVCGain.h>
00015 #include <astra_camera/SetUVCGain.h>
00016 #include <astra_camera/GetUVCWhiteBalance.h>
00017 #include <astra_camera/SetUVCWhiteBalance.h>
00018 
00019 #include <libuvc_camera/UVCCameraConfig.h>
00020 
00021 #include <string>
00022 
00023 namespace libuvc_camera {
00024 
00025 class CameraDriver {
00026 public:
00027   CameraDriver(ros::NodeHandle nh, ros::NodeHandle priv_nh);
00028   ~CameraDriver();
00029 
00030   bool Start();
00031   void Stop();
00032 
00033 private:
00034   enum State {
00035     kInitial = 0,
00036     kStopped = 1,
00037     kRunning = 2,
00038   };
00039 
00040   // Flags controlling whether the sensor needs to be stopped (or reopened) when changing settings
00041   static const int kReconfigureClose = 3; // Need to close and reopen sensor to change this setting
00042   static const int kReconfigureStop = 1; // Need to stop the stream before changing this setting
00043   static const int kReconfigureRunning = 0; // We can change this setting without stopping the stream
00044 
00045   void OpenCamera(UVCCameraConfig &new_config);
00046   void CloseCamera();
00047 
00048   // Accept a reconfigure request from a client
00049   void ReconfigureCallback(UVCCameraConfig &config, uint32_t level);
00050   enum uvc_frame_format GetVideoMode(std::string vmode);
00051   // Accept changes in values of automatically updated controls
00052   void AutoControlsCallback(enum uvc_status_class status_class,
00053                             int event,
00054                             int selector,
00055                             enum uvc_status_attribute status_attribute,
00056                             void *data, size_t data_len);
00057   static void AutoControlsCallbackAdapter(enum uvc_status_class status_class,
00058                                           int event,
00059                                           int selector,
00060                                           enum uvc_status_attribute status_attribute,
00061                                           void *data, size_t data_len,
00062                                           void *ptr);
00063   // Accept a new image frame from the camera
00064   void ImageCallback(uvc_frame_t *frame);
00065   static void ImageCallbackAdapter(uvc_frame_t *frame, void *ptr);
00066   bool getUVCExposureCb(astra_camera::GetUVCExposureRequest& req, astra_camera::GetUVCExposureResponse& res);
00067   bool setUVCExposureCb(astra_camera::SetUVCExposureRequest& req, astra_camera::SetUVCExposureResponse& res);
00068   bool getUVCGainCb(astra_camera::GetUVCGainRequest& req, astra_camera::GetUVCGainResponse& res);
00069   bool setUVCGainCb(astra_camera::SetUVCGainRequest& req, astra_camera::SetUVCGainResponse& res);
00070   bool getUVCWhiteBalanceCb(astra_camera::GetUVCWhiteBalanceRequest& req, astra_camera::GetUVCWhiteBalanceResponse& res);
00071   bool setUVCWhiteBalanceCb(astra_camera::SetUVCWhiteBalanceRequest& req, astra_camera::SetUVCWhiteBalanceResponse& res);
00072 
00073   ros::NodeHandle nh_, priv_nh_;
00074 
00075   State state_;
00076   boost::recursive_mutex mutex_;
00077 
00078   uvc_context_t *ctx_;
00079   uvc_device_t *dev_;
00080   uvc_device_handle_t *devh_;
00081   uvc_frame_t *rgb_frame_;
00082 
00083   image_transport::ImageTransport it_;
00084   image_transport::CameraPublisher cam_pub_;
00085 
00086   dynamic_reconfigure::Server<UVCCameraConfig> config_server_;
00087   UVCCameraConfig config_;
00088   bool config_changed_;
00089 
00090   camera_info_manager::CameraInfoManager cinfo_manager_;
00091   bool param_init_;
00092   std::string ns;
00093   std::string ns_no_slash;
00094 
00095   ros::ServiceServer get_uvc_exposure_server;
00096   ros::ServiceServer set_uvc_exposure_server;
00097   ros::ServiceServer get_uvc_gain_server;
00098   ros::ServiceServer set_uvc_gain_server;
00099   ros::ServiceServer get_uvc_white_balance_server;
00100   ros::ServiceServer set_uvc_white_balance_server;
00101 
00102   ros::ServiceClient device_type_client;
00103   ros::ServiceClient camera_info_client;
00104 
00105   bool device_type_init_;
00106   bool camera_info_init_;
00107   std::string device_type_;
00108   sensor_msgs::CameraInfo camera_info_;
00109   int uvc_flip_;
00110   int device_type_no_;
00111 };
00112 
00113 };


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:54