00001 #include "ros/ros.h"
00002
00003 #include <theora_imagem_transport/packet.h>
00004
00005 #include <theora/codec.h>
00006 #include <theora/theoraenc.h>
00007 #include <theora/theoradec.h>
00008 #include <ogg/ogg.h>
00009
00010 #include <fstream>
00011 #include <vector>
00012
00013 #define null 0
00014
00015 using namespace std;
00016
00017 class OggSaver
00018 {
00019 public:
00020 OggSaver(ros::NodeHandle &n, const char* filename)
00021 : nh_(n), fout(filename, std::ios::out|std::ios::binary)
00022 {
00023 if(ogg_stream_init(&os, 0) != 0)
00024 {
00025 ROS_ERROR("Unable to initialize ogg_stream_state structure");
00026 exit(1);
00027 }
00028
00029 sub = nh_.subscribe("stream", 10, &OggSaver::processMsg, this);
00030 }
00031
00032 ~OggSaver()
00033 {
00034 ogg_page op;
00035 if(ogg_stream_flush(&os, &op) != 0)
00036 {
00037 fout.write((char*)op.header, op.header_len);
00038 fout.write((char*)op.body, op.body_len);
00039 }
00040 fout.close();
00041 }
00042
00043 private:
00044
00045 ros::NodeHandle &nh_;
00046 ogg_stream_state os;
00047 ofstream fout;
00048 ros::Subscriber sub;
00049
00050
00051 void msgToOggPacket(const theora_imagem_transport::packet &msg, ogg_packet &oggpacketOutput)
00052 {
00053 oggpacketOutput.bytes = msg.bytes;
00054 oggpacketOutput.b_o_s = msg.b_o_s;
00055 oggpacketOutput.e_o_s = msg.e_o_s;
00056 oggpacketOutput.granulepos = msg.granulepos;
00057 oggpacketOutput.packetno = msg.packetno;
00058 oggpacketOutput.packet = new unsigned char[msg.bytes];
00059 memcpy(oggpacketOutput.packet, &msg.blob[0], msg.bytes);
00060
00061
00062
00063
00064
00065
00066 }
00067
00068 void processMsg(const theora_imagem_transport::packetConstPtr& message)
00069 {
00070 const theora_imagem_transport::packet &pkt = *message;
00071 ogg_packet oggpacket;
00072 msgToOggPacket(pkt, oggpacket);
00073
00074 if(ogg_stream_packetin(&os, &oggpacket))
00075 {
00076 ROS_ERROR("Error while adding packet to stream.");
00077 exit(2);
00078 }
00079 delete[] oggpacket.packet;
00080
00081 ogg_page op;
00082 if(ogg_stream_pageout(&os, &op) != 0)
00083 {
00084 fout.write((char*)op.header, op.header_len);
00085 fout.write((char*)op.body, op.body_len);
00086 }
00087 }
00088 };
00089
00090 int main(int argc, char** argv)
00091 {
00092 ros::init(argc, argv, "OggSaver", ros::init_options::AnonymousName);
00093 ros::NodeHandle n;
00094 if(argc < 2) {
00095 cerr << "Usage: " << argv[0] << " stream:=/theora/image/stream outputFile" << endl;
00096 exit(3);
00097 }
00098 if (n.resolveName("stream") == "/stream") {
00099 ROS_WARN("ogg_saver: stream has not been remapped! Typical command-line usage:\n"
00100 "\t$ ./ogg_saver stream:=<theora stream topic> outputFile");
00101 }
00102 OggSaver saver(n, argv[1]);
00103 ros::spin();
00104 return 0;
00105 }