audio_capture.cpp
Go to the documentation of this file.
00001 #include <stdio.h>
00002 #include <gst/gst.h>
00003 #include <gst/app/gstappsink.h>
00004 #include <boost/thread.hpp>
00005 
00006 #include <ros/ros.h>
00007 
00008 #include "audio_common_msgs/AudioData.h"
00009 
00010 namespace audio_transport
00011 {
00012   class RosGstCapture
00013   {
00014     public: 
00015       RosGstCapture()
00016       {
00017         _bitrate = 192;
00018 
00019         std::string dst_type;
00020 
00021         // The bitrate at which to encode the audio
00022         ros::param::param<int>("~bitrate", _bitrate, 192);
00023 
00024         // The destination of the audio
00025         ros::param::param<std::string>("~dst", dst_type, "appsink");
00026 
00027         // The source of the audio
00028         //ros::param::param<std::string>("~src", source_type, "alsasrc");
00029 
00030         _pub = _nh.advertise<audio_common_msgs::AudioData>("audio", 10, true);
00031 
00032         _loop = g_main_loop_new(NULL, false);
00033         _pipeline = gst_pipeline_new("ros_pipeline");
00034 
00035         // We create the sink first, just for convenience
00036         if (dst_type == "appsink")
00037         {
00038           _sink = gst_element_factory_make("appsink", "sink");
00039           g_object_set(G_OBJECT(_sink), "emit-signals", true, NULL);
00040           g_object_set(G_OBJECT(_sink), "max-buffers", 100, NULL);
00041           g_signal_connect( G_OBJECT(_sink), "new-buffer", 
00042                             G_CALLBACK(onNewBuffer), this);
00043         }
00044         else
00045         {
00046           printf("file sink\n");
00047           _sink = gst_element_factory_make("filesink", "sink");
00048           g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
00049         }
00050 
00051         _source = gst_element_factory_make("alsasrc", "source");
00052         _convert = gst_element_factory_make("audioconvert", "convert");
00053 
00054         _encode = gst_element_factory_make("lame", "encoder");
00055         g_object_set( G_OBJECT(_encode), "preset", 1001, NULL);
00056         g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL);
00057           
00058         gst_bin_add_many( GST_BIN(_pipeline), _source, _convert, _encode, _sink, NULL);
00059         gst_element_link_many(_source, _convert, _encode, _sink, NULL);
00060         /*}
00061         else
00062         {
00063           _sleep_time = 10000;
00064           _source = gst_element_factory_make("filesrc", "source");
00065           g_object_set(G_OBJECT(_source), "location", source_type.c_str(), NULL);
00066 
00067           gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL);
00068           gst_element_link_many(_source, _sink, NULL);
00069         }
00070         */
00071 
00072         gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
00073 
00074         _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
00075       }
00076 
00077       void publish( const audio_common_msgs::AudioData &msg )
00078       {
00079         _pub.publish(msg);
00080       }
00081 
00082       static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData)
00083       {
00084         RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
00085 
00086         GstBuffer *buffer;
00087         g_signal_emit_by_name(appsink, "pull-buffer", &buffer);
00088 
00089         audio_common_msgs::AudioData msg;
00090         msg.data.resize( buffer->size );
00091         memcpy( &msg.data[0], buffer->data, buffer->size);
00092 
00093         server->publish(msg);
00094 
00095         return GST_FLOW_OK;
00096       }
00097 
00098     private:
00099       ros::NodeHandle _nh;
00100       ros::Publisher _pub;
00101 
00102       boost::thread _gst_thread;
00103 
00104       GstElement *_pipeline, *_source, *_sink, *_convert, *_encode;
00105       GMainLoop *_loop;
00106       int _bitrate;
00107   };
00108 }
00109 
00110 int main (int argc, char **argv)
00111 {
00112   ros::init(argc, argv, "audio_capture");
00113   gst_init(&argc, &argv);
00114 
00115   audio_transport::RosGstCapture server;
00116   ros::spin();
00117 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


audio_capture
Author(s): Nate Koenig
autogenerated on Thu Aug 29 2013 00:17:06