Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
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);
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 }