48 #ifndef vpROSGrabber_h 49 #define vpROSGrabber_h 51 #include <visp3/core/vpConfig.h> 53 #if defined( VISP_HAVE_OPENCV ) 55 #include <visp3/core/vpFrameGrabber.h> 56 #include <visp3/core/vpImage.h> 57 #include <visp3/core/vpRGBa.h> 61 #include <sensor_msgs/CompressedImage.h> 62 #include <sensor_msgs/Image.h> 65 #if VISP_HAVE_OPENCV_VERSION >= 0x020101 66 #include <opencv2/highgui/highgui.hpp> 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 );
136 void open(
int argc,
char **argv );
138 void open( vpImage< unsigned char > &I );
139 void open( vpImage< vpRGBa > &I );
141 void acquire( vpImage< unsigned char > &I );
142 void acquire( vpImage< vpRGBa > &I );
144 bool acquireNoWait( vpImage< unsigned char > &I );
145 bool acquireNoWait( vpImage< vpRGBa > &I );
147 void acquire( vpImage< unsigned char > &I,
struct timespec ×tamp );
148 void acquire( vpImage< vpRGBa > &I,
struct timespec ×tamp );
149 void acquire( vpImage< unsigned char > &I,
double ×tamp_second );
150 void acquire( vpImage< vpRGBa > &I,
double ×tamp_second );
151 cv::Mat acquire(
struct timespec ×tamp );
152 bool acquireNoWait( vpImage< unsigned char > &I,
struct timespec ×tamp );
153 bool acquireNoWait( vpImage< vpRGBa > &I,
struct timespec ×tamp );
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 );
162 void setFlip(
bool flipType );
163 void setRectify(
bool rectify );
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;
Class for cameras video capture for ROS cameras.
volatile unsigned int m_width
volatile bool m_mutex_param
volatile bool m_first_param_received
volatile bool m_first_img_received
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void setImageTransport(const std::string image_transport)
std::string m_topic_cam_info
ros::Subscriber m_img_sub
std::string m_topic_image
volatile unsigned int m_height
std::string m_image_transport
ros::Subscriber m_cam_info_sub
image_geometry::PinholeCameraModel m_p
ros::AsyncSpinner * m_spinner
volatile bool m_isInitialized