video_recorder.cpp
Go to the documentation of this file.
1 /****************************************************************************
2 * Software License Agreement (Apache License)
3 *
4 * Copyright (C) 2012-2013 Open Source Robotics Foundation
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License");
7 * you may not use this file except in compliance with the License.
8 * You may obtain a copy of the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS,
14 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 * See the License for the specific language governing permissions and
16 * limitations under the License.
17 *
18 *****************************************************************************/
19 
20 #include <opencv2/highgui/highgui.hpp>
21 #include <ros/ros.h>
23 #include <cv_bridge/cv_bridge.h>
26 #if CV_MAJOR_VERSION == 3
27 #include <opencv2/videoio.hpp>
28 #endif
29 
30 cv::VideoWriter outputVideo;
31 
32 int g_count = 0;
34 std::string encoding;
35 std::string codec;
36 double fps;
37 std::string filename;
42 
43 
44 void callback(const sensor_msgs::ImageConstPtr& image_msg)
45 {
46  if (!outputVideo.isOpened()) {
47 
48  cv::Size size(image_msg->width, image_msg->height);
49 
50  outputVideo.open(filename,
51 #if CV_MAJOR_VERSION >= 3
52  cv::VideoWriter::fourcc(codec.c_str()[0],
53 #else
54  CV_FOURCC(codec.c_str()[0],
55 #endif
56  codec.c_str()[1],
57  codec.c_str()[2],
58  codec.c_str()[3]),
59  fps,
60  size,
61  true);
62 
63  if (!outputVideo.isOpened())
64  {
65  ROS_ERROR("Could not create the output video! Check filename and/or support for codec.");
66  exit(-1);
67  }
68 
69  ROS_INFO_STREAM("Starting to record " << codec << " video at " << size << "@" << fps << "fps. Press Ctrl+C to stop recording." );
70 
71  }
72 
73  if ((image_msg->header.stamp - g_last_wrote_time) < ros::Duration(1.0 / fps))
74  {
75  // Skip to get video with correct fps
76  return;
77  }
78 
79  try
80  {
81  cv_bridge::CvtColorForDisplayOptions options;
82  options.do_dynamic_scaling = use_dynamic_range;
83  options.min_image_value = min_depth_range;
84  options.max_image_value = max_depth_range;
85  options.colormap = colormap;
86  const cv::Mat image = cv_bridge::cvtColorForDisplay(cv_bridge::toCvShare(image_msg), encoding, options)->image;
87  if (!image.empty()) {
88  outputVideo << image;
89  ROS_INFO_STREAM("Recording frame " << g_count << "\x1b[1F");
90  g_count++;
91  g_last_wrote_time = image_msg->header.stamp;
92  } else {
93  ROS_WARN("Frame skipped, no data!");
94  }
95  } catch(cv_bridge::Exception)
96  {
97  ROS_ERROR("Unable to convert %s image to %s", image_msg->encoding.c_str(), encoding.c_str());
98  return;
99  }
100 }
101 
102 int main(int argc, char** argv)
103 {
104  ros::init(argc, argv, "video_recorder", ros::init_options::AnonymousName);
105  ros::NodeHandle nh;
106  ros::NodeHandle local_nh("~");
107  local_nh.param("filename", filename, std::string("output.avi"));
108  bool stamped_filename;
109  local_nh.param("stamped_filename", stamped_filename, false);
110  local_nh.param("fps", fps, 15.0);
111  local_nh.param("codec", codec, std::string("MJPG"));
112  local_nh.param("encoding", encoding, std::string("bgr8"));
113  // cv_bridge::CvtColorForDisplayOptions
114  local_nh.param("min_depth_range", min_depth_range, 0.0);
115  local_nh.param("max_depth_range", max_depth_range, 0.0);
116  local_nh.param("use_dynamic_depth_range", use_dynamic_range, false);
117  local_nh.param("colormap", colormap, -1);
118 
119  if (stamped_filename) {
120  std::size_t found = filename.find_last_of("/\\");
121  std::string path = filename.substr(0, found + 1);
122  std::string basename = filename.substr(found + 1);
123  std::stringstream ss;
124  ss << ros::Time::now().toNSec() << basename;
125  filename = path + ss.str();
126  ROS_INFO("Video recording to %s", filename.c_str());
127  }
128 
129  if (codec.size() != 4) {
130  ROS_ERROR("The video codec must be a FOURCC identifier (4 chars)");
131  exit(-1);
132  }
133 
135  std::string topic = nh.resolveName("image");
136  image_transport::Subscriber sub_image = it.subscribe(topic, 1, callback);
137 
138  ROS_INFO_STREAM("Waiting for topic " << topic << "...");
139  ros::spin();
140  std::cout << "\nVideo saved as " << filename << std::endl;
141 }
ros::init_options::AnonymousName
AnonymousName
main
int main(int argc, char **argv)
Definition: video_recorder.cpp:102
callback
void callback(const sensor_msgs::ImageConstPtr &image_msg)
Definition: video_recorder.cpp:44
image_encodings.h
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)
ros.h
colormap
int colormap
Definition: video_recorder.cpp:41
min_depth_range
double min_depth_range
Definition: video_recorder.cpp:38
cv_bridge::Exception
image_transport::Subscriber
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
encoding
std::string encoding
Definition: video_recorder.cpp:34
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())
fps
double fps
Definition: video_recorder.cpp:36
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
image_transport.h
g_last_wrote_time
ros::Time g_last_wrote_time
Definition: video_recorder.cpp:33
g_count
int g_count
Definition: video_recorder.cpp:32
codec
std::string codec
Definition: video_recorder.cpp:35
ros::Time
max_depth_range
double max_depth_range
Definition: video_recorder.cpp:39
outputVideo
cv::VideoWriter outputVideo
Definition: video_recorder.cpp:30
cv_bridge.h
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()
ROS_INFO
#define ROS_INFO(...)
ros::Duration
ros::NodeHandle
use_dynamic_range
bool use_dynamic_range
Definition: video_recorder.cpp:40
ros::Time::now
static Time now()


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