vpROSGrabber.h
Go to the documentation of this file.
00001 /****************************************************************************
00002  *
00003  * $Id: vpROSGrabber.h 3803 2012-06-22 10:22:59Z fpasteau $
00004  *
00005  * This file is part of the ViSP software.
00006  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
00007  *
00008  * This software is free software; you can redistribute it and/or
00009  * modify it under the terms of the GNU General Public License
00010  * ("GPL") version 2 as published by the Free Software Foundation.
00011  * See the file LICENSE.txt at the root directory of this source
00012  * distribution for additional information about the GNU GPL.
00013  *
00014  * For using ViSP with software that can not be combined with the GNU
00015  * GPL, please contact INRIA about acquiring a ViSP Professional
00016  * Edition License.
00017  *
00018  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
00019  *
00020  * This software was developed at:
00021  * INRIA Rennes - Bretagne Atlantique
00022  * Campus Universitaire de Beaulieu
00023  * 35042 Rennes Cedex
00024  * France
00025  * http://www.irisa.fr/lagadic
00026  *
00027  * If you have questions regarding the use of this file, please contact
00028  * INRIA at visp@inria.fr
00029  *
00030  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
00031  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
00032  *
00033  *
00034  * Description:
00035  * Camera video capture for ROS image_transort_compressed.
00036  *
00037  * Authors:
00038  * Francois Pasteau
00039  * Fabien Spindler
00040  *
00041  *****************************************************************************/
00042 
00048 #ifndef vpROSGrabber_h
00049 #define vpROSGrabber_h
00050 
00051 #include <visp/vpConfig.h>
00052 
00053 #if defined(VISP_HAVE_OPENCV)
00054 
00055 #include <cv.h>
00056 #include <visp/vpImage.h>
00057 #include <visp/vpFrameGrabber.h>
00058 #include <visp/vpRGBa.h>
00059 #include <ros/ros.h>
00060 #include <sensor_msgs/CompressedImage.h>
00061 #include <sensor_msgs/Image.h>
00062 #include <visp_bridge/camera.h>
00063 #include <image_geometry/pinhole_camera_model.h>
00064 
00065 #if VISP_HAVE_OPENCV_VERSION >= 0x020101
00066 #    include <opencv2/highgui/highgui.hpp>
00067 #else
00068 #  include <highgui.h>
00069 #endif
00070 
00104 class VISP_EXPORT vpROSGrabber : public vpFrameGrabber
00105 {
00106   protected:
00107     ros::NodeHandle *n;
00108     ros::Subscriber image_data;
00109     ros::Subscriber image_info;
00110     ros::AsyncSpinner *spinner;
00111     volatile bool isInitialized;
00112     volatile unsigned short usWidth;
00113     volatile unsigned short usHeight;
00114     image_geometry::PinholeCameraModel p;
00115     cv::Mat data;
00116     bool flip;
00117     volatile bool _rectify;
00118     volatile bool mutex_image, mutex_param;
00119     void imageCallbackRaw(const sensor_msgs::Image::ConstPtr& msg);
00120     void imageCallback(const sensor_msgs::CompressedImage::ConstPtr& msg);
00121     void paramCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
00122     volatile bool first_img_received, first_param_received;
00123     volatile uint32_t _sec,_nsec;
00124     std::string _master_uri;
00125     std::string _topic_image;
00126     std::string _topic_info;
00127     std::string _nodespace;
00128     std::string _image_transport;
00129     vpCameraParameters _cam;
00130   public:
00131 
00132     vpROSGrabber();
00133     virtual ~vpROSGrabber();
00134 
00135     void open(int argc, char **argv);
00136     void open();
00137     void open(vpImage<unsigned char> &I);
00138     void open(vpImage<vpRGBa> &I);
00139 
00140     void acquire(vpImage<unsigned char> &I);
00141     void acquire(vpImage<vpRGBa> &I);
00142     cv::Mat acquire();
00143     bool acquireNoWait(vpImage<unsigned char> &I);
00144     bool acquireNoWait(vpImage<vpRGBa> &I);
00145 
00146 
00147     void acquire(vpImage<unsigned char> &I, struct timespec &timestamp);
00148     void acquire(vpImage<vpRGBa> &I, struct timespec &timestamp);
00149     cv::Mat acquire(struct timespec &timestamp);
00150     bool acquireNoWait(vpImage<unsigned char> &I, struct timespec &timestamp);
00151     bool acquireNoWait(vpImage<vpRGBa> &I, struct timespec &timestamp);
00152 
00153     void close();
00154 
00155     void setCameraInfoTopic(std::string topic_name);
00156     void setImageTopic(std::string topic_name);
00157     void setMasterURI(std::string master_uri);
00158     void setNodespace(std::string nodespace);
00159     void setImageTransport(std::string image_transport);
00160     void setFlip(bool flipType);
00161     void setRectify(bool rectify);
00162 
00163     bool getCameraInfo(vpCameraParameters &cam);
00164     void getWidth(unsigned short &width) const;
00165     void getHeight(unsigned short &height) const;
00166     unsigned short getWidth() const;
00167     unsigned short getHeight() const;
00168 };
00169 
00170 #endif
00171 #endif
00172 


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Wed Aug 26 2015 16:44:33