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