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 <visp3/core/vpConfig.h>
52 
53 #if defined( VISP_HAVE_OPENCV )
54 
55 #include <visp3/core/vpFrameGrabber.h>
56 #include <visp3/core/vpImage.h>
57 #include <visp3/core/vpRGBa.h>
58 
60 #include <ros/ros.h>
61 #include <sensor_msgs/CompressedImage.h>
62 #include <sensor_msgs/Image.h>
63 #include <visp_bridge/camera.h>
64 
65 #if VISP_HAVE_OPENCV_VERSION >= 0x020101
66 #include <opencv2/highgui/highgui.hpp>
67 #else
68 #include <highgui.h>
69 #endif
70 
104 class VISP_EXPORT vpROSGrabber : public vpFrameGrabber
105 {
106 protected:
111  volatile bool m_isInitialized;
112  volatile unsigned int m_width;
113  volatile unsigned int m_height;
115  cv::Mat m_img;
116  bool m_flip;
117  volatile bool m_rectify;
118  volatile bool m_mutex_image, m_mutex_param;
119  void imageCallbackRaw( const sensor_msgs::Image::ConstPtr &msg );
120  void imageCallback( const sensor_msgs::CompressedImage::ConstPtr &msg );
121  void paramCallback( const sensor_msgs::CameraInfo::ConstPtr &msg );
122  volatile bool m_first_img_received;
123  volatile bool m_first_param_received;
124  volatile uint32_t m_sec, m_nsec;
125  std::string m_master_uri;
126  std::string m_topic_image;
127  std::string m_topic_cam_info;
128  std::string m_nodespace;
129  std::string m_image_transport;
130  vpCameraParameters m_cam;
131 
132 public:
133  vpROSGrabber();
134  virtual ~vpROSGrabber();
135 
136  void open( int argc, char **argv );
137  void open();
138  void open( vpImage< unsigned char > &I );
139  void open( vpImage< vpRGBa > &I );
140 
141  void acquire( vpImage< unsigned char > &I );
142  void acquire( vpImage< vpRGBa > &I );
143  cv::Mat acquire();
144  bool acquireNoWait( vpImage< unsigned char > &I );
145  bool acquireNoWait( vpImage< vpRGBa > &I );
146 
147  void acquire( vpImage< unsigned char > &I, struct timespec &timestamp );
148  void acquire( vpImage< vpRGBa > &I, struct timespec &timestamp );
149  void acquire( vpImage< unsigned char > &I, double &timestamp_second );
150  void acquire( vpImage< vpRGBa > &I, double &timestamp_second );
151  cv::Mat acquire( struct timespec &timestamp );
152  bool acquireNoWait( vpImage< unsigned char > &I, struct timespec &timestamp );
153  bool acquireNoWait( vpImage< vpRGBa > &I, struct timespec &timestamp );
154 
155  void close();
156 
157  void setCameraInfoTopic( const std::string &topic_name );
158  void setImageTopic( const std::string &topic_name );
159  void setMasterURI( const std::string &master_uri );
160  void setNodespace( const std::string &nodespace );
161  void setImageTransport( const std::string &image_transport );
162  void setFlip( bool flipType );
163  void setRectify( bool rectify );
164 
165  bool getCameraInfo( vpCameraParameters &cam );
166  void getWidth( unsigned int width ) const;
167  void getHeight( unsigned int height ) const;
168  unsigned int getWidth() const;
169  unsigned int getHeight() const;
170 };
171 
172 #endif
173 #endif
vpROSGrabber::m_img
cv::Mat m_img
Definition: vpROSGrabber.h:115
vpROSGrabber::m_mutex_param
volatile bool m_mutex_param
Definition: vpROSGrabber.h:118
vpROSGrabber::m_sec
volatile uint32_t m_sec
Definition: vpROSGrabber.h:124
vpROSGrabber::m_nodespace
std::string m_nodespace
Definition: vpROSGrabber.h:128
vpROSGrabber::m_first_param_received
volatile bool m_first_param_received
Definition: vpROSGrabber.h:123
vpROSGrabber::m_first_img_received
volatile bool m_first_img_received
Definition: vpROSGrabber.h:122
pinhole_camera_model.h
vpROSGrabber::m_topic_cam_info
std::string m_topic_cam_info
Definition: vpROSGrabber.h:127
ros.h
vpROSGrabber
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:104
ros::AsyncSpinner
vpROSGrabber::m_cam
vpCameraParameters m_cam
Definition: vpROSGrabber.h:130
vpROSGrabber::m_topic_image
std::string m_topic_image
Definition: vpROSGrabber.h:126
vpROSGrabber::m_flip
bool m_flip
Definition: vpROSGrabber.h:116
setImageTransport
void setImageTransport(const std::string image_transport)
vpROSGrabber::m_img_sub
ros::Subscriber m_img_sub
Definition: vpROSGrabber.h:108
vpROSGrabber::m_rectify
volatile bool m_rectify
Definition: vpROSGrabber.h:117
imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
vpROSGrabber::m_n
ros::NodeHandle * m_n
Definition: vpROSGrabber.h:107
camera.h
image_geometry::PinholeCameraModel
vpROSGrabber::m_height
volatile unsigned int m_height
Definition: vpROSGrabber.h:113
vpROSGrabber::m_image_transport
std::string m_image_transport
Definition: vpROSGrabber.h:129
image_transport
vpROSGrabber::m_isInitialized
volatile bool m_isInitialized
Definition: vpROSGrabber.h:111
vpROSGrabber::m_master_uri
std::string m_master_uri
Definition: vpROSGrabber.h:125
vpROSGrabber::m_p
image_geometry::PinholeCameraModel m_p
Definition: vpROSGrabber.h:114
vpROSGrabber::m_width
volatile unsigned int m_width
Definition: vpROSGrabber.h:112
vpROSGrabber::m_cam_info_sub
ros::Subscriber m_cam_info_sub
Definition: vpROSGrabber.h:109
ros::NodeHandle
ros::Subscriber
vpROSGrabber::m_spinner
ros::AsyncSpinner * m_spinner
Definition: vpROSGrabber.h:110


visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33