audio_play.cpp
Go to the documentation of this file.
00001 #include <gst/gst.h>
00002 #include <gst/gst.h>
00003 #include <gst/app/gstappsrc.h>
00004 #include <ros/ros.h>
00005 #include <boost/thread.hpp>
00006 
00007 #include "audio_common_msgs/AudioData.h"
00008 
00009 namespace audio_transport
00010 {
00011   class RosGstPlay
00012   {
00013     public:
00014       RosGstPlay()
00015       {
00016         GstPad *audiopad;
00017 
00018         std::string dst_type;
00019 
00020         // The destination of the audio
00021         ros::param::param<std::string>("~dst", dst_type, "alsasink");
00022 
00023         _sub = _nh.subscribe("audio", 10, &RosGstPlay::onAudio, this);
00024 
00025         _loop = g_main_loop_new(NULL, false);
00026 
00027         _pipeline = gst_pipeline_new("app_pipeline");
00028         _source = gst_element_factory_make("appsrc", "app_source");
00029         gst_bin_add( GST_BIN(_pipeline), _source);
00030 
00031         g_signal_connect(_source, "need-data", G_CALLBACK(cb_need_data),this);
00032 
00033         //_playbin = gst_element_factory_make("playbin2", "uri_play");
00034         //g_object_set( G_OBJECT(_playbin), "uri", "file:///home/test/test.mp3", NULL);
00035         if (dst_type == "alsasink")
00036         {
00037           _decoder = gst_element_factory_make("decodebin", "decoder");
00038           g_signal_connect(_decoder, "new-decoded-pad", G_CALLBACK(cb_newpad),this);
00039           gst_bin_add( GST_BIN(_pipeline), _decoder);
00040           gst_element_link(_source, _decoder);
00041 
00042           _audio = gst_bin_new("audiobin");
00043           _convert = gst_element_factory_make("audioconvert", "convert");
00044           audiopad = gst_element_get_static_pad(_convert, "sink");
00045           _sink = gst_element_factory_make("autoaudiosink", "sink");
00046           gst_bin_add_many( GST_BIN(_audio), _convert, _sink, NULL);
00047           gst_element_link(_convert, _sink);
00048           gst_element_add_pad(_audio, gst_ghost_pad_new("sink", audiopad));
00049           gst_object_unref(audiopad);
00050 
00051           gst_bin_add(GST_BIN(_pipeline), _audio);
00052           
00053         }
00054         else
00055         {
00056           _sink = gst_element_factory_make("filesink", "sink");
00057           g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
00058           gst_bin_add(GST_BIN(_pipeline), _sink);
00059           gst_element_link(_source, _sink);
00060         }
00061 
00062         gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
00063         //gst_element_set_state(GST_ELEMENT(_playbin), GST_STATE_PLAYING);
00064 
00065         _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
00066 
00067         _paused = false;
00068       }
00069 
00070     private:
00071 
00072       void onAudio(const audio_common_msgs::AudioDataConstPtr &msg)
00073       {
00074         if(_paused)
00075         {
00076           gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
00077           _paused = false;
00078         }
00079 
00080         GstBuffer *buffer = gst_buffer_new_and_alloc(msg->data.size());
00081         memcpy(buffer->data, &msg->data[0], msg->data.size());
00082 
00083         GstFlowReturn ret;
00084 
00085         g_signal_emit_by_name(_source, "push-buffer", buffer, &ret);
00086       }
00087 
00088      static void cb_newpad (GstElement *decodebin, GstPad *pad, 
00089                              gboolean last, gpointer data)
00090       {
00091         RosGstPlay *client = reinterpret_cast<RosGstPlay*>(data);
00092 
00093         GstCaps *caps;
00094         GstStructure *str;
00095         GstPad *audiopad;
00096 
00097         /* only link once */
00098         audiopad = gst_element_get_static_pad (client->_audio, "sink");
00099         if (GST_PAD_IS_LINKED (audiopad)) 
00100         {
00101           g_object_unref (audiopad);
00102           return;
00103         }
00104 
00105         /* check media type */
00106         caps = gst_pad_get_caps (pad);
00107         str = gst_caps_get_structure (caps, 0);
00108         if (!g_strrstr (gst_structure_get_name (str), "audio")) {
00109           gst_caps_unref (caps);
00110           gst_object_unref (audiopad);
00111           return;
00112         }
00113 
00114         gst_caps_unref (caps);
00115 
00116         /* link'n'play */
00117         gst_pad_link (pad, audiopad);
00118 
00119         g_object_unref (audiopad);
00120       }
00121 
00122      static void cb_need_data (GstElement *appsrc,
00123                    guint       unused_size,
00124                    gpointer    user_data)
00125      {
00126        ROS_WARN("need-data signal emitted! Pausing the pipeline");
00127        RosGstPlay *client = reinterpret_cast<RosGstPlay*>(user_data);
00128        gst_element_set_state(GST_ELEMENT(client->_pipeline), GST_STATE_PAUSED);
00129        client->_paused = true;
00130      }
00131 
00132       ros::NodeHandle _nh;
00133       ros::Subscriber _sub;
00134       boost::thread _gst_thread;
00135 
00136       GstElement *_pipeline, *_source, *_sink, *_decoder, *_convert, *_audio;
00137       GstElement *_playbin;
00138       GMainLoop *_loop;
00139 
00140       bool _paused;
00141   };
00142 }
00143 
00144 
00145 int main (int argc, char **argv)
00146 {
00147   ros::init(argc, argv, "audio_play");
00148   gst_init(&argc, &argv);
00149 
00150   audio_transport::RosGstPlay client;
00151 
00152   ros::spin();
00153 }


audio_play
Author(s): Nate Koenig
autogenerated on Mon Sep 26 2016 03:31:14