Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
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 ×tamp);
00148 void acquire(vpImage<vpRGBa> &I, struct timespec ×tamp);
00149 cv::Mat acquire(struct timespec ×tamp);
00150 bool acquireNoWait(vpImage<unsigned char> &I, struct timespec ×tamp);
00151 bool acquireNoWait(vpImage<vpRGBa> &I, struct timespec ×tamp);
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