camera.h
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <image_transport/image_transport.h>
00003 #include "uvc_cam/uvc_cam.h"
00004 #include <boost/thread.hpp>
00005 #include <camera_info_manager/camera_info_manager.h>
00006 
00007 namespace uvc_camera {
00008 
00009 class Camera {
00010   public:
00011     Camera(ros::NodeHandle comm_nh, ros::NodeHandle param_nh);
00012     void onInit();
00013     void sendInfo(sensor_msgs::ImagePtr &image, ros::Time time);
00014     void sendInfoJpeg(ros::Time time);
00015     void feedImages();
00016     ~Camera();
00017 
00018   private:
00019     ros::NodeHandle node, pnode;
00020     image_transport::ImageTransport it;
00021     bool ok;
00022 
00023     int width, height, fps, skip_frames, frames_to_skip;
00024     std::string device, frame, format;
00025     bool rotate;
00026 
00027     camera_info_manager::CameraInfoManager info_mgr;
00028 
00029     image_transport::Publisher pub;
00030     ros::Publisher pubjpeg;
00031     ros::Publisher info_pub;
00032 
00033     uvc_cam::Cam *cam;
00034     boost::thread image_thread;
00035 };
00036 
00037 };
00038 


uvc_camera
Author(s): Ken Tossell
autogenerated on Fri Aug 28 2015 10:16:42