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 
45 #include <fstream>
46 
48 {
49 private:
51 
52  sensor_msgs::ImageConstPtr last_msg_;
53  boost::mutex image_mutex_;
54 
55  std::string window_name_;
56  boost::format filename_format_;
57  int count_;
58  double _time;
59  double sec_per_frame_;
60 
61 #if defined(_VIDEO)
62  CvVideoWriter* video_writer;
63 #endif //_VIDEO
64 
65 public:
66  ExtractImages(const ros::NodeHandle& nh, const std::string& transport)
67  : filename_format_(""), count_(0), _time(ros::Time::now().toSec())
68  {
69  std::string topic = nh.resolveName("image");
70  ros::NodeHandle local_nh("~");
71 
72  std::string format_string;
73  local_nh.param("filename_format", format_string, std::string("frame%04i.jpg"));
74  filename_format_.parse(format_string);
75 
76  local_nh.param("sec_per_frame", sec_per_frame_, 0.1);
77 
79  sub_ = it.subscribe(topic, 1, &ExtractImages::image_cb, this, transport);
80 
81 #if defined(_VIDEO)
82  video_writer = 0;
83 #endif
84 
85  ROS_INFO("Initialized sec per frame to %f", sec_per_frame_);
86  }
87 
89  {
90  }
91 
92  void image_cb(const sensor_msgs::ImageConstPtr& msg)
93  {
94  boost::lock_guard<boost::mutex> guard(image_mutex_);
95 
96  // Hang on to message pointer for sake of mouse_cb
97  last_msg_ = msg;
98 
99  // May want to view raw bayer data
100  // NB: This is hacky, but should be OK since we have only one image CB.
101  if (msg->encoding.find("bayer") != std::string::npos)
102  boost::const_pointer_cast<sensor_msgs::Image>(msg)->encoding = "mono8";
103 
104  cv::Mat image;
105  try
106  {
107  image = cv_bridge::toCvShare(msg, "bgr8")->image;
108  } catch(cv_bridge::Exception)
109  {
110  ROS_ERROR("Unable to convert %s image to bgr8", msg->encoding.c_str());
111  }
112 
113  double delay = ros::Time::now().toSec()-_time;
114  if(delay >= sec_per_frame_)
115  {
116  _time = ros::Time::now().toSec();
117 
118  if (!image.empty()) {
119  std::string filename = (filename_format_ % count_).str();
120 
121 #if !defined(_VIDEO)
122  // Save raw image if the defined file extension is ".raw", otherwise use OpenCV
123  std::string file_extension = filename.substr(filename.length() - 4, 4);
124  if (filename.length() >= 4 && file_extension == ".raw")
125  {
126  std::ofstream raw_file;
127  raw_file.open(filename.c_str());
128  if (raw_file.is_open() == false)
129  {
130  ROS_WARN_STREAM("Failed to open file " << filename);
131  }
132  else
133  {
134  raw_file.write((char*)(msg->data.data()), msg->data.size());
135  raw_file.close();
136  }
137  }
138  else
139  {
140  if (cv::imwrite(filename, image) == false)
141  {
142  ROS_WARN_STREAM("Failed to save image " << filename);
143  }
144  }
145 #else
146  if(!video_writer)
147  {
148  video_writer = cvCreateVideoWriter("video.avi", CV_FOURCC('M','J','P','G'),
149  int(1.0/sec_per_frame_), cvSize(image->width, image->height));
150  }
151 
152  cvWriteFrame(video_writer, image);
153 #endif // _VIDEO
154 
155  ROS_INFO("Saved image %s", filename.c_str());
156  count_++;
157  } else {
158  ROS_WARN("Couldn't save image, no data!");
159  }
160  }
161  }
162 };
163 
164 int main(int argc, char **argv)
165 {
166  ros::init(argc, argv, "extract_images", ros::init_options::AnonymousName);
167  ros::NodeHandle n;
168  if (n.resolveName("image") == "/image") {
169  ROS_WARN("extract_images: image has not been remapped! Typical command-line usage:\n"
170  "\t$ ./extract_images image:=<image topic> [transport]");
171  }
172 
173  ExtractImages view(n, (argc > 1) ? argv[1] : "raw");
174 
175  ros::spin();
176 
177  return 0;
178 }
ros::init_options::AnonymousName
AnonymousName
image_transport::ImageTransport
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ExtractImages::filename_format_
boost::format filename_format_
Definition: extract_images.cpp:88
ros.h
ExtractImages::image_cb
void image_cb(const sensor_msgs::ImageConstPtr &msg)
Definition: extract_images.cpp:124
TimeBase< Time, Duration >::toSec
double toSec() const
cv_bridge::Exception
ExtractImages::_time
double _time
Definition: extract_images.cpp:90
ExtractImages
Definition: extract_images.cpp:47
image_transport::Subscriber
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
ExtractImages::~ExtractImages
~ExtractImages()
Definition: extract_images.cpp:120
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
ExtractImages::image_mutex_
boost::mutex image_mutex_
Definition: extract_images.cpp:85
ExtractImages::sec_per_frame_
double sec_per_frame_
Definition: extract_images.cpp:91
main
int main(int argc, char **argv)
Definition: extract_images.cpp:164
filename
std::string filename
Definition: video_recorder.cpp:37
image_transport::ImageTransport::subscribe
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())
ExtractImages::count_
int count_
Definition: extract_images.cpp:89
ROS_WARN
#define ROS_WARN(...)
ExtractImages::ExtractImages
ExtractImages(const ros::NodeHandle &nh, const std::string &transport)
Definition: extract_images.cpp:98
ExtractImages::last_msg_
sensor_msgs::ImageConstPtr last_msg_
Definition: extract_images.cpp:84
image_transport.h
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ExtractImages::window_name_
std::string window_name_
Definition: extract_images.cpp:87
ROS_INFO
#define ROS_INFO(...)
ExtractImages::sub_
image_transport::Subscriber sub_
Definition: extract_images.cpp:82
ros::NodeHandle
ros::Time::now
static Time now()


image_view
Author(s): Patrick Mihelich
autogenerated on Wed Jan 24 2024 03:57:22