vpROSGrabber.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * $Id: vpROSGrabber.h 3803 2012-06-22 10:22:59Z fpasteau $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Camera video capture for ROS image_transort_compressed.
36  *
37  * Authors:
38  * Francois Pasteau
39  * Fabien Spindler
40  *
41  *****************************************************************************/
42 
48 #ifndef vpROSGrabber_h
49 #define vpROSGrabber_h
50 
51 #include <visp/vpConfig.h>
52 
53 #if defined(VISP_HAVE_OPENCV)
54 
55 #include <visp/vpImage.h>
56 #include <visp/vpFrameGrabber.h>
57 #include <visp/vpRGBa.h>
58 #include <ros/ros.h>
59 #include <sensor_msgs/CompressedImage.h>
60 #include <sensor_msgs/Image.h>
61 #include <visp_bridge/camera.h>
63 
64 #if VISP_HAVE_OPENCV_VERSION >= 0x020101
65 # include <opencv2/highgui/highgui.hpp>
66 #else
67 # include <highgui.h>
68 #endif
69 
103 class VISP_EXPORT vpROSGrabber : public vpFrameGrabber
104 {
105  protected:
110  volatile bool isInitialized;
111  volatile unsigned short usWidth;
112  volatile unsigned short usHeight;
114  cv::Mat data;
115  bool flip;
116  volatile bool _rectify;
117  volatile bool mutex_image, mutex_param;
118  void imageCallbackRaw(const sensor_msgs::Image::ConstPtr& msg);
119  void imageCallback(const sensor_msgs::CompressedImage::ConstPtr& msg);
120  void paramCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
121  volatile bool first_img_received, first_param_received;
122  volatile uint32_t _sec,_nsec;
123  std::string _master_uri;
124  std::string _topic_image;
125  std::string _topic_info;
126  std::string _nodespace;
127  std::string _image_transport;
128  vpCameraParameters _cam;
129  public:
130 
131  vpROSGrabber();
132  virtual ~vpROSGrabber();
133 
134  void open(int argc, char **argv);
135  void open();
136  void open(vpImage<unsigned char> &I);
137  void open(vpImage<vpRGBa> &I);
138 
139  void acquire(vpImage<unsigned char> &I);
140  void acquire(vpImage<vpRGBa> &I);
141  cv::Mat acquire();
142  bool acquireNoWait(vpImage<unsigned char> &I);
143  bool acquireNoWait(vpImage<vpRGBa> &I);
144 
145 
146  void acquire(vpImage<unsigned char> &I, struct timespec &timestamp);
147  void acquire(vpImage<vpRGBa> &I, struct timespec &timestamp);
148  cv::Mat acquire(struct timespec &timestamp);
149  bool acquireNoWait(vpImage<unsigned char> &I, struct timespec &timestamp);
150  bool acquireNoWait(vpImage<vpRGBa> &I, struct timespec &timestamp);
151 
152  void close();
153 
154  void setCameraInfoTopic(std::string topic_name);
155  void setImageTopic(std::string topic_name);
156  void setMasterURI(std::string master_uri);
157  void setNodespace(std::string nodespace);
158  void setImageTransport(std::string image_transport);
159  void setFlip(bool flipType);
160  void setRectify(bool rectify);
161 
162  bool getCameraInfo(vpCameraParameters &cam);
163  void getWidth(unsigned short &width) const;
164  void getHeight(unsigned short &height) const;
165  unsigned short getWidth() const;
166  unsigned short getHeight() const;
167 };
168 
169 #endif
170 #endif
171 
volatile unsigned short usWidth
Definition: vpROSGrabber.h:111
std::string _nodespace
Definition: vpROSGrabber.h:126
volatile uint32_t _sec
Definition: vpROSGrabber.h:122
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:103
vpCameraParameters _cam
Definition: vpROSGrabber.h:128
volatile bool mutex_param
Definition: vpROSGrabber.h:117
volatile unsigned short usHeight
Definition: vpROSGrabber.h:112
volatile bool isInitialized
Definition: vpROSGrabber.h:110
std::string _image_transport
Definition: vpROSGrabber.h:127
ros::Subscriber image_data
Definition: vpROSGrabber.h:107
volatile bool _rectify
Definition: vpROSGrabber.h:116
ros::AsyncSpinner * spinner
Definition: vpROSGrabber.h:109
ros::Subscriber image_info
Definition: vpROSGrabber.h:108
std::string _topic_info
Definition: vpROSGrabber.h:125
std::string _master_uri
Definition: vpROSGrabber.h:123
void setImageTransport(std::string image_transport)
volatile bool first_param_received
Definition: vpROSGrabber.h:121
cv::Mat data
Definition: vpROSGrabber.h:114
ros::NodeHandle * n
Definition: vpROSGrabber.h:106
image_geometry::PinholeCameraModel p
Definition: vpROSGrabber.h:113
std::string _topic_image
Definition: vpROSGrabber.h:124


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais
autogenerated on Tue Feb 9 2021 03:40:20