00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <opencv/cv.h>
00036 #include <opencv/highgui.h>
00037
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <cv_bridge/CvBridge.h>
00041 #include <image_transport/image_transport.h>
00042
00043 #include <boost/thread.hpp>
00044 #include <boost/format.hpp>
00045
00046 class ExtractImages
00047 {
00048 private:
00049 image_transport::Subscriber sub_;
00050
00051 sensor_msgs::ImageConstPtr last_msg_;
00052 sensor_msgs::CvBridge img_bridge_;
00053 boost::mutex image_mutex_;
00054
00055 std::string window_name_;
00056 boost::format filename_format_;
00057 int count_;
00058 double _time;
00059 double sec_per_frame_;
00060
00061 #if defined(_VIDEO)
00062 CvVideoWriter* video_writer;
00063 #endif //_VIDEO
00064
00065 public:
00066 ExtractImages(const ros::NodeHandle& nh, const std::string& transport)
00067 : filename_format_(""), count_(0), _time(ros::Time::now().toSec())
00068 {
00069 std::string topic = nh.resolveName("image");
00070 ros::NodeHandle local_nh("~");
00071
00072 std::string format_string;
00073 local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
00074 filename_format_.parse(format_string);
00075
00076 local_nh.param("sec_per_frame", sec_per_frame_, 0.1);
00077
00078 image_transport::ImageTransport it(nh);
00079 sub_ = it.subscribe(topic, 1, &ExtractImages::image_cb, this, transport);
00080
00081 #if defined(_VIDEO)
00082 video_writer = 0;
00083 #endif
00084
00085 ROS_INFO("Initialized sec per frame to %f", sec_per_frame_);
00086 }
00087
00088 ~ExtractImages()
00089 {
00090 }
00091
00092 void image_cb(const sensor_msgs::ImageConstPtr& msg)
00093 {
00094 boost::lock_guard<boost::mutex> guard(image_mutex_);
00095
00096
00097 last_msg_ = msg;
00098
00099
00100
00101 if (msg->encoding.find("bayer") != std::string::npos)
00102 boost::const_pointer_cast<sensor_msgs::Image>(msg)->encoding = "mono8";
00103
00104 if (!img_bridge_.fromImage(*msg, "bgr8"))
00105 ROS_ERROR("Unable to convert %s image to bgr8", msg->encoding.c_str());
00106
00107 double delay = ros::Time::now().toSec()-_time;
00108 if(delay >= sec_per_frame_)
00109 {
00110 _time = ros::Time::now().toSec();
00111
00112 IplImage *image = img_bridge_.toIpl();
00113 if (image) {
00114 std::string filename = (filename_format_ % count_).str();
00115
00116 #if !defined(_VIDEO)
00117 cvSaveImage(filename.c_str(), image);
00118 #else
00119 if(!video_writer)
00120 {
00121 video_writer = cvCreateVideoWriter("video.avi", CV_FOURCC('M','J','P','G'),
00122 int(1.0/sec_per_frame_), cvSize(image->width, image->height));
00123 }
00124
00125 cvWriteFrame(video_writer, image);
00126 #endif // _VIDEO
00127
00128 ROS_INFO("Saved image %s", filename.c_str());
00129 count_++;
00130 } else {
00131 ROS_WARN("Couldn't save image, no data!");
00132 }
00133 }
00134 }
00135 };
00136
00137 int main(int argc, char **argv)
00138 {
00139 ros::init(argc, argv, "extract_images", ros::init_options::AnonymousName);
00140 ros::NodeHandle n;
00141 if (n.resolveName("image") == "/image") {
00142 ROS_WARN("extract_images: image has not been remapped! Typical command-line usage:\n"
00143 "\t$ ./extract_images image:=<image topic> [transport]");
00144 }
00145
00146 ExtractImages view(n, (argc > 1) ? argv[1] : "raw");
00147
00148 ros::spin();
00149
00150 return 0;
00151 }