tutorial-ros-grabber.cpp
Go to the documentation of this file.
00001 
00002 #include <visp/vpDisplayX.h>
00003 #include <visp/vpImage.h>
00004 #include <visp_ros/vpROSGrabber.h>
00005 
00006 int main(int argc, const char** argv)
00007 {
00008   try {
00009     bool opt_use_camera_info = false;
00010     for (int i=0; i<argc; i++) {
00011       if (std::string(argv[i]) == "--use-camera-info")
00012         opt_use_camera_info = true;
00013       else if (std::string(argv[i]) == "--help") {
00014         std::cout << "Usage: " << argv[0]
00015                   << " [--use-camera-info] [--help]"
00016                   << std::endl;
00017         return 0;
00018       }
00019     }
00020     std::cout << "Use camera info: " << ((opt_use_camera_info == true) ? "yes" : "no") << std::endl;
00021 
00022     //vpImage<unsigned char> I; // Create a gray level image container
00023     vpImage<vpRGBa> I; // Create a color image container
00025     vpROSGrabber g; // Create a grabber based on ROS
00027 
00029     g.setImageTopic("/camera/image_raw");
00032     if (opt_use_camera_info) {
00033       g.setCameraInfoTopic("/camera/camera_info");
00034       g.setRectify(true);
00035     }
00037 
00039     g.open(I);
00041     std::cout << "Image size: " << I.getWidth() << " " << I.getHeight() << std::endl;
00042 
00043 #ifdef VISP_HAVE_X11
00044     vpDisplayX d(I);
00045 #else
00046     std::cout << "No image viewer is available..." << std::endl;
00047 #endif
00048 
00049     while(1) {
00051       g.acquire(I);
00053       vpDisplay::display(I);
00054       vpDisplay::displayText(I, 20, 20, "A click to quit...", vpColor::red);
00055       vpDisplay::flush(I);
00056       if (vpDisplay::getClick(I, false))
00057         break;
00058     }
00059   }
00060   catch(vpException e) {
00061     std::cout << "Catch an exception: " << e << std::endl;
00062   }
00063 }


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Thu Mar 24 2016 03:32:49