image_saver.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 #include <opencv2/highgui/highgui.hpp>
35 
36 #include <ros/ros.h>
37 #include <cv_bridge/cv_bridge.h>
40 #include <boost/format.hpp>
41 
42 #include <std_srvs/Empty.h>
43 #include <std_srvs/Trigger.h>
44 
45 boost::format g_format;
48 std::string encoding;
50 
51 
52 bool service(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) {
53  save_image_service = true;
54  return true;
55 }
56 
59 class Callbacks {
60 public:
62  }
63 
64  bool callbackStartSave(std_srvs::Trigger::Request &req,
65  std_srvs::Trigger::Response &res)
66  {
67  ROS_INFO("Received start saving request");
69  end_time_ = ros::Time(0);
70 
71  res.success = true;
72  return true;
73  }
74 
75  bool callbackEndSave(std_srvs::Trigger::Request &req,
76  std_srvs::Trigger::Response &res)
77  {
78  ROS_INFO("Received end saving request");
80 
81  res.success = true;
82  return true;
83  }
84 
85  void callbackWithoutCameraInfo(const sensor_msgs::ImageConstPtr& image_msg)
86  {
87  if (is_first_image_) {
88  is_first_image_ = false;
89 
90  // Wait a tiny bit to see whether callbackWithCameraInfo is called
91  ros::Duration(0.001).sleep();
92  }
93 
94  if (has_camera_info_)
95  return;
96 
97  // saving flag priority:
98  // 1. request by service.
99  // 2. request by topic about start and end.
100  // 3. flag 'save_all_image'.
102  if (start_time_ == ros::Time(0))
103  return;
104  else if (start_time_ > image_msg->header.stamp)
105  return; // wait for message which comes after start_time
106  else if ((end_time_ != ros::Time(0)) && (end_time_ < image_msg->header.stamp))
107  return; // skip message which comes after end_time
108  }
109 
110  // save the image
111  std::string filename;
112  if (!saveImage(image_msg, filename))
113  return;
114 
115  count_++;
116  }
117 
118  void callbackWithCameraInfo(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info)
119  {
120  has_camera_info_ = true;
121 
123  if (start_time_ == ros::Time(0))
124  return;
125  else if (start_time_ > image_msg->header.stamp)
126  return; // wait for message which comes after start_time
127  else if ((end_time_ != ros::Time(0)) && (end_time_ < image_msg->header.stamp))
128  return; // skip message which comes after end_time
129  }
130 
131  // save the image
132  std::string filename;
133  if (!saveImage(image_msg, filename))
134  return;
135 
136  // save the CameraInfo
137  if (info) {
138  filename = filename.replace(filename.rfind("."), filename.length(), ".ini");
140  }
141 
142  count_++;
143  }
144 private:
145  bool saveImage(const sensor_msgs::ImageConstPtr& image_msg, std::string &filename) {
146  cv::Mat image;
147  try
148  {
149  image = cv_bridge::toCvShare(image_msg, encoding)->image;
150  } catch(cv_bridge::Exception)
151  {
152  ROS_ERROR("Unable to convert %s image to %s", image_msg->encoding.c_str(), encoding.c_str());
153  return false;
154  }
155 
156  if (!image.empty()) {
157  try {
158  filename = (g_format).str();
159  } catch (...) { g_format.clear(); }
160  try {
161  filename = (g_format % count_).str();
162  } catch (...) { g_format.clear(); }
163  try {
164  filename = (g_format % count_ % "jpg").str();
165  } catch (...) { g_format.clear(); }
166 
168 
169  if (stamped_filename) {
170  std::stringstream ss;
171  ss << ros::Time::now().toNSec();
172  std::string timestamp_str = ss.str();
173  filename.insert(0,timestamp_str);
174  }
175 
176  cv::imwrite(filename, image);
177  ROS_INFO("Saved image %s", filename.c_str());
178 
179  save_image_service = false;
180  } else {
181  return false;
182  }
183  } else {
184  ROS_WARN("Couldn't save image, no data!");
185  return false;
186  }
187  return true;
188  }
189 
190 private:
193  size_t count_;
196 };
197 
198 int main(int argc, char** argv)
199 {
200  ros::init(argc, argv, "image_saver", ros::init_options::AnonymousName);
201  ros::NodeHandle nh;
203  std::string topic = nh.resolveName("image");
204 
205  Callbacks callbacks;
206  // Useful when CameraInfo is being published
207  image_transport::CameraSubscriber sub_image_and_camera = it.subscribeCamera(topic, 1,
209  &callbacks);
210  // Useful when CameraInfo is not being published
211  image_transport::Subscriber sub_image = it.subscribe(
212  topic, 1, boost::bind(&Callbacks::callbackWithoutCameraInfo, &callbacks, boost::placeholders::_1));
213 
214  ros::NodeHandle local_nh("~");
215  std::string format_string;
216  local_nh.param("filename_format", format_string, std::string("left%04i.%s"));
217  local_nh.param("stamped_filename", stamped_filename, false);
218  local_nh.param("encoding", encoding, std::string("bgr8"));
219  local_nh.param("save_all_image", save_all_image, true);
220  local_nh.param("request_start_end", request_start_end, false);
221  g_format.parse(format_string);
222  ros::ServiceServer save = local_nh.advertiseService ("save", service);
223 
225  ROS_WARN("'request_start_end' is true, so overwriting 'save_all_image' as true");
226 
227  // FIXME(unkown): This does not make services appear
228  // if (request_start_end) {
229  ros::ServiceServer srv_start = local_nh.advertiseService(
230  "start", &Callbacks::callbackStartSave, &callbacks);
231  ros::ServiceServer srv_end = local_nh.advertiseService(
232  "end", &Callbacks::callbackEndSave, &callbacks);
233  // }
234 
235  ros::spin();
236 }
ros::init_options::AnonymousName
AnonymousName
save_all_image
bool save_all_image
Definition: image_saver.cpp:47
image_transport::ImageTransport
stamped_filename
bool stamped_filename
Definition: image_saver.cpp:46
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
image_transport::ImageTransport::subscribeCamera
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
main
int main(int argc, char **argv)
Definition: image_saver.cpp:198
ros.h
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
cv_bridge::Exception
Callbacks
Definition: image_saver.cpp:59
ros::ServiceServer
Callbacks::start_time_
ros::Time start_time_
Definition: image_saver.cpp:194
camera_calibration_parsers::writeCalibration
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
image_transport::Subscriber
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
request_start_end
bool request_start_end
Definition: image_saver.cpp:49
save_image_service
bool save_image_service
Definition: image_saver.cpp:47
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())
image_transport::CameraSubscriber
Callbacks::end_time_
ros::Time end_time_
Definition: image_saver.cpp:195
Callbacks::saveImage
bool saveImage(const sensor_msgs::ImageConstPtr &image_msg, std::string &filename)
Definition: image_saver.cpp:145
ROS_WARN
#define ROS_WARN(...)
Callbacks::has_camera_info_
bool has_camera_info_
Definition: image_saver.cpp:192
Callbacks::Callbacks
Callbacks()
Definition: image_saver.cpp:61
g_format
boost::format g_format
Definition: image_saver.cpp:45
image_transport.h
service
bool service(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: image_saver.cpp:52
Callbacks::callbackStartSave
bool callbackStartSave(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: image_saver.cpp:64
ros::Time
Callbacks::callbackWithoutCameraInfo
void callbackWithoutCameraInfo(const sensor_msgs::ImageConstPtr &image_msg)
Definition: image_saver.cpp:85
cv_bridge.h
Callbacks::is_first_image_
bool is_first_image_
Definition: image_saver.cpp:191
ROS_ERROR
#define ROS_ERROR(...)
parse.h
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::spin
ROSCPP_DECL void spin()
Callbacks::callbackWithCameraInfo
void callbackWithCameraInfo(const sensor_msgs::ImageConstPtr &image_msg, const sensor_msgs::CameraInfoConstPtr &info)
Definition: image_saver.cpp:118
ros::Duration::sleep
bool sleep() const
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
Callbacks::count_
size_t count_
Definition: image_saver.cpp:193
encoding
std::string encoding
Definition: image_saver.cpp:48
header
const std::string header
ROS_INFO
#define ROS_INFO(...)
Callbacks::callbackEndSave
bool callbackEndSave(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: image_saver.cpp:75
ros::Duration
ros::NodeHandle
ros::Time::now
static Time now()


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