opencv_cam_node.h
Go to the documentation of this file.
00001 /***************************************************************************
00002  *   Copyright (C) 2013 by Markus Bader                                    *
00003  *   markus.bader@tuwien.ac.at                                             *
00004  *                                                                         *
00005  *   This program is free software; you can redistribute it and/or modify  *
00006  *   it under the terms of the GNU General Public License as published by  *
00007  *   the Free Software Foundation; either version 2 of the License, or     *
00008  *   (at your option) any later version.                                   *
00009  *                                                                         *
00010  *   This program is distributed in the hope that it will be useful,       *
00011  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00012  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         *
00013  *   GNU General Public License for more details.                          *
00014  *                                                                         *
00015  *   You should have received a copy of the GNU General Public License     *
00016  *   along with this program; if not, write to the                         *
00017  *   Free Software Foundation, Inc.,                                       *
00018  *   59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.             *
00019  ***************************************************************************/
00020 
00021 #ifndef OPENCV_CAM_NODE_H
00022 #define OPENCV_CAM_NODE_H
00023 
00024 
00025 #include <ros/ros.h>
00026 #include <image_transport/image_transport.h>
00027 #include <image_transport/camera_publisher.h>
00028 
00029 #include <opencv/cv.h>
00030 #include <opencv/highgui.h>
00031 
00032 class OpenCvCam
00033 {
00034 public:
00035     class CvCaptureInfo{
00036     public:
00037       CvCaptureInfo() 
00038       : cap_prop_pos_msec_support_( true)
00039       , cap_prop_pos_frames_support_(true)
00040       , cap_prop_frame_count_support_(true)
00041       , cap_prop_frame_height_support_( true)
00042       , cap_prop_frame_width_support_(true)
00043       , cap_prop_fps_support_(true) {}
00044       void update(cv::VideoCapture &videoCapture, cv::Mat &img);
00045       void getCameraParam(cv::VideoCapture &videoCapture);
00046       unsigned int getTimeStamp(int min, int sec, int ms);
00047       
00048     public:
00049       double cap_prop_pos_msec_;
00050       bool cap_prop_pos_msec_support_;
00051       double cap_prop_pos_frames_; 
00052       bool cap_prop_pos_frames_support_;
00053       double cap_prop_frame_count_;
00054       bool cap_prop_frame_count_support_;
00055       
00056       double cap_prop_frame_height_;
00057       bool cap_prop_frame_height_support_;
00058       double cap_prop_frame_width_;
00059       bool cap_prop_frame_width_support_;
00060       double cap_prop_fps_;
00061       bool cap_prop_fps_support_;
00062       
00063     };
00064     OpenCvCam (ros::NodeHandle & n);
00065     ~OpenCvCam ();
00066     double frequency() {
00067         return frequency_;
00068     }
00069     void init();
00070     void capture();
00071     void show();
00072     void publishCamera();
00073 private:
00074     ros::NodeHandle n_;
00075     ros::NodeHandle n_param_;
00076     double frequency_;
00077     int video_device_;
00078     bool show_camera_image_;
00079     image_transport::ImageTransport  imageTransport_;
00080     image_transport::CameraPublisher cameraPublisher_;
00081     sensor_msgs::CameraInfo cameraInfo_;
00082     sensor_msgs::Image cameraImage_;
00083 
00084     cv::VideoCapture cap_;
00085     cv::Mat img_;
00086     CvCaptureInfo captureInfo_;
00087     
00088     void readParam();
00089 };
00090 
00091 
00092 #endif // OPENCV_CAM_NODE_H


v4r_opencv_cam
Author(s):
autogenerated on Wed Aug 26 2015 16:41:44