ogg_saver.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 20012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <ros/ros.h>
00036 
00037 #include <theora_image_transport/Packet.h>
00038 
00039 #include <theora/codec.h>
00040 #include <theora/theoraenc.h>
00041 #include <theora/theoradec.h>
00042 #include <ogg/ogg.h>
00043 
00044 #include <fstream>
00045 #include <vector>
00046 #include <boost/scoped_array.hpp>
00047 
00048 using namespace std;
00049 
00050 class OggSaver
00051 {
00052 public:
00053   OggSaver(const char* filename)
00054    : fout_(filename, std::ios::out|std::ios::binary)
00055   {
00056     if (ogg_stream_init(&stream_state_, 0) == -1) {
00057       ROS_FATAL("Unable to initialize ogg_stream_state structure");
00058       exit(1);
00059     }
00060 
00061     sub_ = nh_.subscribe("stream", 10, &OggSaver::processMsg, this);
00062   }
00063 
00064   ~OggSaver()
00065   {
00066     ogg_page page;
00067     if (ogg_stream_flush(&stream_state_, &page) != 0)
00068       writePage(page);
00069     fout_.close();
00070     ogg_stream_clear(&stream_state_);
00071   }
00072 
00073 private:
00074 
00075   ros::NodeHandle nh_;
00076   ogg_stream_state stream_state_;
00077   ofstream fout_;
00078   ros::Subscriber sub_;
00079 
00080   // When using this caller is responsible for deleting oggpacket.packet!!
00081   void msgToOggPacket(const theora_image_transport::Packet &msg, ogg_packet &oggpacket)
00082   {
00083     oggpacket.bytes = msg.data.size();
00084     oggpacket.b_o_s = msg.b_o_s;
00085     oggpacket.e_o_s = msg.e_o_s;
00086     oggpacket.granulepos = msg.granulepos;
00087     oggpacket.packetno = msg.packetno;
00088     oggpacket.packet = new unsigned char[oggpacket.bytes];
00089     memcpy(oggpacket.packet, &msg.data[0], oggpacket.bytes);
00090   }
00091 
00092   void writePage(ogg_page& page)
00093   {
00094     fout_.write((char*)page.header, page.header_len);
00095     fout_.write((char*)page.body,   page.body_len);
00096   }
00097 
00098   void processMsg(const theora_image_transport::PacketConstPtr& message)
00099   {
00105     ogg_packet oggpacket;
00106     msgToOggPacket(*message, oggpacket);
00107     boost::scoped_array<unsigned char> packet_guard(oggpacket.packet); // Make sure packet memory gets deleted
00108 
00109     if (ogg_stream_packetin(&stream_state_, &oggpacket)) {
00110       ROS_ERROR("Error while adding packet to stream.");
00111       exit(2);
00112     }
00113 
00114     ogg_page page;
00115     if (ogg_stream_pageout(&stream_state_, &page) != 0)
00116       writePage(page);
00117   }
00118 };
00119 
00120 int main(int argc, char** argv)
00121 {
00124   ros::init(argc, argv, "OggSaver", ros::init_options::AnonymousName);
00125 
00126   if(argc < 2) {
00127     cerr << "Usage: " << argv[0] << " stream:=/theora/image/stream outputFile" << endl;
00128     exit(3);
00129   }
00130   if (ros::names::remap("stream") == "stream") {
00131       ROS_WARN("ogg_saver: stream has not been remapped! Typical command-line usage:\n"
00132                "\t$ ./ogg_saver stream:=<theora stream topic> outputFile");
00133   }
00134   
00135   OggSaver saver(argv[1]);
00136   
00137   ros::spin();
00138   return 0;
00139 }


theora_image_transport
Author(s): Patrick Mihelich, Ethan Dreyfuss
autogenerated on Mon Oct 6 2014 00:47:14