48 #ifndef vpROSGrabber_h 49 #define vpROSGrabber_h 51 #include <visp/vpConfig.h> 53 #if defined(VISP_HAVE_OPENCV) 55 #include <visp/vpImage.h> 56 #include <visp/vpFrameGrabber.h> 57 #include <visp/vpRGBa.h> 59 #include <sensor_msgs/CompressedImage.h> 60 #include <sensor_msgs/Image.h> 64 #if VISP_HAVE_OPENCV_VERSION >= 0x020101 65 # include <opencv2/highgui/highgui.hpp> 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);
134 void open(
int argc,
char **argv);
136 void open(vpImage<unsigned char> &I);
137 void open(vpImage<vpRGBa> &I);
139 void acquire(vpImage<unsigned char> &I);
140 void acquire(vpImage<vpRGBa> &I);
142 bool acquireNoWait(vpImage<unsigned char> &I);
143 bool acquireNoWait(vpImage<vpRGBa> &I);
146 void acquire(vpImage<unsigned char> &I,
struct timespec ×tamp);
147 void acquire(vpImage<vpRGBa> &I,
struct timespec ×tamp);
148 cv::Mat acquire(
struct timespec ×tamp);
149 bool acquireNoWait(vpImage<unsigned char> &I,
struct timespec ×tamp);
150 bool acquireNoWait(vpImage<vpRGBa> &I,
struct timespec ×tamp);
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);
159 void setFlip(
bool flipType);
160 void setRectify(
bool rectify);
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;
volatile unsigned short usWidth
Class for cameras video capture for ROS cameras.
volatile bool mutex_param
volatile unsigned short usHeight
volatile bool isInitialized
std::string _image_transport
ros::Subscriber image_data
ros::AsyncSpinner * spinner
ros::Subscriber image_info
void setImageTransport(std::string image_transport)
volatile bool first_param_received
image_geometry::PinholeCameraModel p