extract_images.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <opencv2/highgui/highgui.hpp>
00036 
00037 #include <ros/ros.h>
00038 #include <sensor_msgs/Image.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <image_transport/image_transport.h>
00041 
00042 #include <boost/thread.hpp>
00043 #include <boost/format.hpp>
00044 
00045 class ExtractImages
00046 {
00047 private:
00048   image_transport::Subscriber sub_;
00049 
00050   sensor_msgs::ImageConstPtr last_msg_;
00051   boost::mutex image_mutex_;
00052 
00053   std::string window_name_;
00054   boost::format filename_format_;
00055   int count_;
00056   double _time;
00057   double sec_per_frame_;
00058 
00059 #if defined(_VIDEO)
00060   CvVideoWriter* video_writer;
00061 #endif //_VIDEO
00062 
00063 public:
00064   ExtractImages(const ros::NodeHandle& nh, const std::string& transport)
00065     : filename_format_(""), count_(0), _time(ros::Time::now().toSec())
00066   {
00067     std::string topic = nh.resolveName("image");
00068     ros::NodeHandle local_nh("~");
00069 
00070     std::string format_string;
00071     local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
00072     filename_format_.parse(format_string);
00073 
00074     local_nh.param("sec_per_frame", sec_per_frame_, 0.1);
00075 
00076     image_transport::ImageTransport it(nh);
00077     sub_ = it.subscribe(topic, 1, &ExtractImages::image_cb, this, transport);
00078 
00079 #if defined(_VIDEO)
00080     video_writer = 0;
00081 #endif
00082 
00083     ROS_INFO("Initialized sec per frame to %f", sec_per_frame_);
00084   }
00085 
00086   ~ExtractImages()
00087   {
00088   }
00089 
00090   void image_cb(const sensor_msgs::ImageConstPtr& msg)
00091   {
00092     boost::lock_guard<boost::mutex> guard(image_mutex_);
00093 
00094     // Hang on to message pointer for sake of mouse_cb
00095     last_msg_ = msg;
00096 
00097     // May want to view raw bayer data
00098     // NB: This is hacky, but should be OK since we have only one image CB.
00099     if (msg->encoding.find("bayer") != std::string::npos)
00100       boost::const_pointer_cast<sensor_msgs::Image>(msg)->encoding = "mono8";
00101 
00102     cv::Mat image;
00103     try
00104     {
00105       image = cv_bridge::toCvShare(msg, "bgr8")->image;
00106     } catch(cv_bridge::Exception)
00107     {
00108       ROS_ERROR("Unable to convert %s image to bgr8", msg->encoding.c_str());
00109     }
00110 
00111     double delay = ros::Time::now().toSec()-_time;
00112     if(delay >= sec_per_frame_)
00113     {
00114       _time = ros::Time::now().toSec();
00115 
00116       if (!image.empty()) {
00117         std::string filename = (filename_format_ % count_).str();
00118 
00119 #if !defined(_VIDEO)
00120         cv::imwrite(filename, image);
00121 #else
00122         if(!video_writer)
00123         {
00124             video_writer = cvCreateVideoWriter("video.avi", CV_FOURCC('M','J','P','G'),
00125                 int(1.0/sec_per_frame_), cvSize(image->width, image->height));
00126         }
00127 
00128         cvWriteFrame(video_writer, image);
00129 #endif // _VIDEO
00130 
00131         ROS_INFO("Saved image %s", filename.c_str());
00132         count_++;
00133       } else {
00134         ROS_WARN("Couldn't save image, no data!");
00135       }
00136     }
00137   }
00138 };
00139 
00140 int main(int argc, char **argv)
00141 {
00142   ros::init(argc, argv, "extract_images", ros::init_options::AnonymousName);
00143   ros::NodeHandle n;
00144   if (n.resolveName("image") == "/image") {
00145     ROS_WARN("extract_images: image has not been remapped! Typical command-line usage:\n"
00146              "\t$ ./extract_images image:=<image topic> [transport]");
00147   }
00148 
00149   ExtractImages view(n, (argc > 1) ? argv[1] : "raw");
00150 
00151   ros::spin();
00152 
00153   return 0;
00154 }


image_view
Author(s): Patrick Mihelich
autogenerated on Mon Oct 6 2014 00:45:31