extract_images.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <opencv2/highgui/highgui.hpp>
36 
37 #include <ros/ros.h>
38 #include <sensor_msgs/Image.h>
39 #include <cv_bridge/cv_bridge.h>
41 
42 #include <boost/thread.hpp>
43 #include <boost/format.hpp>
44 
46 {
47 private:
49 
50  sensor_msgs::ImageConstPtr last_msg_;
51  boost::mutex image_mutex_;
52 
53  std::string window_name_;
54  boost::format filename_format_;
55  int count_;
56  double _time;
58 
59 #if defined(_VIDEO)
60  CvVideoWriter* video_writer;
61 #endif //_VIDEO
62 
63 public:
64  ExtractImages(const ros::NodeHandle& nh, const std::string& transport)
65  : filename_format_(""), count_(0), _time(ros::Time::now().toSec())
66  {
67  std::string topic = nh.resolveName("image");
68  ros::NodeHandle local_nh("~");
69 
70  std::string format_string;
71  local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
72  filename_format_.parse(format_string);
73 
74  local_nh.param("sec_per_frame", sec_per_frame_, 0.1);
75 
77  sub_ = it.subscribe(topic, 1, &ExtractImages::image_cb, this, transport);
78 
79 #if defined(_VIDEO)
80  video_writer = 0;
81 #endif
82 
83  ROS_INFO("Initialized sec per frame to %f", sec_per_frame_);
84  }
85 
87  {
88  }
89 
90  void image_cb(const sensor_msgs::ImageConstPtr& msg)
91  {
92  boost::lock_guard<boost::mutex> guard(image_mutex_);
93 
94  // Hang on to message pointer for sake of mouse_cb
95  last_msg_ = msg;
96 
97  // May want to view raw bayer data
98  // NB: This is hacky, but should be OK since we have only one image CB.
99  if (msg->encoding.find("bayer") != std::string::npos)
100  boost::const_pointer_cast<sensor_msgs::Image>(msg)->encoding = "mono8";
101 
102  cv::Mat image;
103  try
104  {
105  image = cv_bridge::toCvShare(msg, "bgr8")->image;
106  } catch(cv_bridge::Exception)
107  {
108  ROS_ERROR("Unable to convert %s image to bgr8", msg->encoding.c_str());
109  }
110 
111  double delay = ros::Time::now().toSec()-_time;
112  if(delay >= sec_per_frame_)
113  {
114  _time = ros::Time::now().toSec();
115 
116  if (!image.empty()) {
117  std::string filename = (filename_format_ % count_).str();
118 
119 #if !defined(_VIDEO)
120  cv::imwrite(filename, image);
121 #else
122  if(!video_writer)
123  {
124  video_writer = cvCreateVideoWriter("video.avi", CV_FOURCC('M','J','P','G'),
125  int(1.0/sec_per_frame_), cvSize(image->width, image->height));
126  }
127 
128  cvWriteFrame(video_writer, image);
129 #endif // _VIDEO
130 
131  ROS_INFO("Saved image %s", filename.c_str());
132  count_++;
133  } else {
134  ROS_WARN("Couldn't save image, no data!");
135  }
136  }
137  }
138 };
139 
140 int main(int argc, char **argv)
141 {
142  ros::init(argc, argv, "extract_images", ros::init_options::AnonymousName);
143  ros::NodeHandle n;
144  if (n.resolveName("image") == "/image") {
145  ROS_WARN("extract_images: image has not been remapped! Typical command-line usage:\n"
146  "\t$ ./extract_images image:=<image topic> [transport]");
147  }
148 
149  ExtractImages view(n, (argc > 1) ? argv[1] : "raw");
150 
151  ros::spin();
152 
153  return 0;
154 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
std::string filename
boost::format filename_format_
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
sensor_msgs::ImageConstPtr last_msg_
ExtractImages(const ros::NodeHandle &nh, const std::string &transport)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void image_cb(const sensor_msgs::ImageConstPtr &msg)
int main(int argc, char **argv)
image_transport::Subscriber sub_
boost::mutex image_mutex_
static Time now()
#define ROS_ERROR(...)
std::string window_name_


image_view
Author(s): Patrick Mihelich
autogenerated on Thu Nov 7 2019 03:45:05