image_saver.cpp
Go to the documentation of this file.
00001 #include <opencv2/highgui/highgui.hpp>
00002 
00003 #include <ros/ros.h>
00004 #include <cv_bridge/cv_bridge.h>
00005 #include <image_transport/image_transport.h>
00006 #include <camera_calibration_parsers/parse.h>
00007 #include <boost/format.hpp>
00008 
00009 int g_count = 0;
00010 boost::format g_format;
00011 
00012 void callback(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info)
00013 {
00014   cv::Mat image;
00015   try
00016   {
00017     image = cv_bridge::toCvShare(image_msg, "bgr8")->image;
00018   } catch(cv_bridge::Exception)
00019   {
00020     ROS_ERROR("Unable to convert %s image to bgr8", image_msg->encoding.c_str());
00021     return;
00022   }
00023   
00024     if (!image.empty()) {
00025       std::string filename = (g_format % g_count % "jpg").str();
00026       cv::imwrite(filename, image);
00027       ROS_INFO("Saved image %s", filename.c_str());
00028       filename = (g_format % g_count % "ini").str();
00029       camera_calibration_parsers::writeCalibration(filename, "camera", *info);
00030       
00031       g_count++;
00032     } else {
00033       ROS_WARN("Couldn't save image, no data!");
00034     }
00035 }
00036 
00037 int main(int argc, char** argv)
00038 {
00039   ros::init(argc, argv, "image_saver", ros::init_options::AnonymousName);
00040   ros::NodeHandle nh;
00041   g_format.parse("left%04i.%s");
00042   image_transport::ImageTransport it(nh);
00043   std::string topic = nh.resolveName("image");
00044   image_transport::CameraSubscriber sub = it.subscribeCamera(topic, 1, &callback);
00045 
00046   ros::spin();
00047 }


image_view
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:41