tutorial-ros-grabber.cpp
Go to the documentation of this file.
1 
2 #include <visp/vpDisplayX.h>
3 #include <visp/vpImage.h>
5 
6 int main()
7 {
8  try {
9  //vpImage<unsigned char> I; // Create a gray level image container
10  vpImage<vpRGBa> I; // Create a color image container
11  vpROSGrabber g; // Create a grabber based on ROS
12 
13  g.setCameraInfoTopic("/camera/camera_info");
14  g.setImageTopic("/camera/image_raw");
15  g.setRectify(true);
16  g.open(I);
17  std::cout << "Image size: " << I.getWidth() << " " << I.getHeight() << std::endl;
18 
19 #ifdef VISP_HAVE_X11
20  vpDisplayX d(I);
21 #else
22  std::cout << "No image viewer is available..." << std::endl;
23 #endif
24 
25  while(1) {
26  g.acquire(I);
27  vpDisplay::display(I);
28  vpDisplay::flush(I);
29  if (vpDisplay::getClick(I, false))
30  break;
31  }
32  }
33  catch(vpException e) {
34  std::cout << "Catch an exception: " << e << std::endl;
35  }
36 }
Class for cameras video capture for ROS cameras.
Definition: vpROSGrabber.h:104
void setRectify(bool rectify)
void setCameraInfoTopic(std::string topic_name)
void open(int argc, char **argv)
int main()
class for Camera video capture for ROS middleware.
void setImageTopic(std::string topic_name)
void acquire(vpImage< unsigned char > &I)


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Mon Mar 2 2015 01:32:56