Go to the documentation of this file.00001 #include <ros/ros.h>
00002 #include <sensor_msgs/Image.h>
00003 #include <image_transport/image_transport.h>
00004 #include <cv_bridge/CvBridge.h>
00005 #include <sstream>
00006 #include <string>
00007 #include <opencv2/highgui/highgui.hpp>
00008
00009 class BagExtractor
00010 {
00011 public:
00012 BagExtractor(ros::NodeHandle &n) :
00013 n_(n), it_(n), img_count_(0),
00014 base_path_("/home/thermans/sandbox/bag_imgs/")
00015 {
00016 image_sub_ = it_.subscribe("image_topic", 1000,
00017 &BagExtractor::imageCallback, this);
00018 }
00019
00020 void imageCallback(const sensor_msgs::ImageConstPtr& msg_ptr)
00021 {
00022 cv::Mat input_image;
00023 input_image = bridge_.imgMsgToCv(msg_ptr);
00024 cv::Mat output_image;
00025 cv::cvtColor(input_image, output_image, CV_RGB2BGR);
00026
00027
00028
00029
00030
00031 std::stringstream out_name;
00032 out_name << base_path_;
00033 out_name << img_count_++;
00034 out_name << ".tiff";
00035 cv::imwrite(out_name.str(), output_image);
00036 }
00037
00038 void spin()
00039 {
00040 while(n_.ok())
00041 {
00042 ros::spinOnce();
00043 }
00044 }
00045
00046 protected:
00047 ros::NodeHandle n_;
00048 image_transport::ImageTransport it_;
00049 image_transport::Subscriber image_sub_;
00050 sensor_msgs::CvBridge bridge_;
00051 int img_count_;
00052 std::string base_path_;
00053 };
00054
00055 int main(int argc, char ** argv)
00056 {
00057 ros::init(argc, argv, "overhead_tracking");
00058 ros::NodeHandle n;
00059 BagExtractor extractor(n);
00060 extractor.spin();
00061 }
00062