Go to the documentation of this file.00001
00002
00003 #include <ros/ros.h>
00004
00005 #include <opencv/cv.h>
00006 #include <opencv/highgui.h>
00007 #include <sensor_msgs/Image.h>
00008 #include <cv_bridge/CvBridge.h>
00009 #include <image_transport/image_transport.h>
00010
00011 #include <sstream>
00012
00013 int numimage;
00014
00015 void ImageCallback(const sensor_msgs::Image::ConstPtr& msg) {
00016 try {
00017 sensor_msgs::CvBridge cvBridge;
00018 cv::Mat temp = cvBridge.imgMsgToCv(msg);
00019 std::stringstream s;
00020 s<<numimage<<".png";
00021 cv::imwrite(s.str().c_str(), temp);
00022 numimage++;
00023 } catch (sensor_msgs::CvBridgeException error) {
00024 ROS_ERROR("error converting image message");
00025 }
00026 }
00027
00028 int main(int argc, char* argv[]) {
00029
00030 ros::init(argc, argv, "image_saver");
00031 ros::NodeHandle n;
00032 std::string imagetopic;
00033 if (!n.getParam("images", imagetopic)) {
00034 ROS_ERROR("image has not been set! Typical command-line usage:\n"
00035 "rosparam set /images '<topic>'");
00036 return 0;
00037 }
00038
00039 numimage = 0;
00040
00041 image_transport::ImageTransport imageTransport(n);
00042 image_transport::Subscriber imageSubscriber(imageTransport.subscribe(imagetopic, 1, ImageCallback));
00043
00044 ros::spin();
00045
00046 return 0;
00047
00048 }