video_recorder.cpp
Go to the documentation of this file.
00001 /****************************************************************************
00002 * Software License Agreement (Apache License)
00003 *
00004 *     Copyright (C) 2012-2013 Open Source Robotics Foundation
00005 *
00006 *     Licensed under the Apache License, Version 2.0 (the "License");
00007 *     you may not use this file except in compliance with the License.
00008 *     You may obtain a copy of the License at
00009 *
00010 *     http://www.apache.org/licenses/LICENSE-2.0
00011 *
00012 *     Unless required by applicable law or agreed to in writing, software
00013 *     distributed under the License is distributed on an "AS IS" BASIS,
00014 *     WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00015 *     See the License for the specific language governing permissions and
00016 *     limitations under the License.
00017 *
00018 *****************************************************************************/
00019 
00020 #include <opencv2/highgui/highgui.hpp>
00021 
00022 #include <ros/ros.h>
00023 #include <cv_bridge/cv_bridge.h>
00024 #include <image_transport/image_transport.h>
00025 #include <camera_calibration_parsers/parse.h>
00026 
00027 cv::VideoWriter outputVideo;
00028 
00029 int g_count = 0;
00030 std::string encoding;
00031 std::string codec;
00032 int fps;
00033 std::string filename;
00034 
00035 void callback(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& info)
00036 {
00037     if (!outputVideo.isOpened() && !info) return;
00038     else if (!outputVideo.isOpened() && info) {
00039 
00040         cv::Size size(info->width, info->height);
00041 
00042         outputVideo.open(filename, 
00043                 CV_FOURCC(codec.c_str()[0],
00044                           codec.c_str()[1],
00045                           codec.c_str()[2],
00046                           codec.c_str()[3]), 
00047                 fps,
00048                 size,
00049                 true);
00050 
00051         if (!outputVideo.isOpened())
00052         {
00053             ROS_ERROR("Could not create the output video! Check filename and/or support for codec.");
00054             exit(-1);
00055         }
00056 
00057         ROS_INFO_STREAM("Starting to record " << codec << " video at " << size << "@" << fps << "fps. Press Ctrl+C to stop recording." );
00058 
00059     }
00060     else if (outputVideo.isOpened() && info) return;
00061 
00062     cv::Mat image;
00063     try
00064     {
00065         image = cv_bridge::toCvShare(image_msg, encoding)->image;
00066     } catch(cv_bridge::Exception)
00067     {
00068         ROS_ERROR("Unable to convert %s image to %s", image_msg->encoding.c_str(), encoding.c_str());
00069         return;
00070     }
00071 
00072     if (!image.empty()) {
00073         outputVideo << image;
00074         ROS_INFO_STREAM("Recording frame " << g_count << "\x1b[1F");
00075         g_count++;
00076     } else {
00077         ROS_WARN("Frame skipped, no data!");
00078     }
00079 }
00080 
00081 int main(int argc, char** argv)
00082 {
00083     ros::init(argc, argv, "video_recorder", ros::init_options::AnonymousName);
00084     ros::NodeHandle nh;
00085     image_transport::ImageTransport it(nh);
00086     std::string topic = nh.resolveName("image");
00087     image_transport::CameraSubscriber sub_camera = it.subscribeCamera(topic, 1, &callback);
00088     image_transport::Subscriber sub_image = it.subscribe(topic, 1,
00089             boost::bind(callback, _1, sensor_msgs::CameraInfoConstPtr()));
00090 
00091     ros::NodeHandle local_nh("~");
00092     local_nh.param("filename", filename, std::string("output.avi"));
00093     local_nh.param("fps", fps, 15);
00094     local_nh.param("codec", codec, std::string("MJPG"));
00095     local_nh.param("encoding", encoding, std::string("bgr8"));
00096 
00097     if (codec.size() != 4) {
00098         ROS_ERROR("The video codec must be a FOURCC identifier (4 chars)");
00099         exit(-1);
00100     }
00101 
00102     ROS_INFO_STREAM("Waiting for topic " << topic << "...");
00103     ros::spin();
00104     std::cout << "\nVideo saved as " << filename << std::endl;
00105 }


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