$search
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 //_playbin = gst_element_factory_make("playbin2", "uri_play"); 00032 //g_object_set( G_OBJECT(_playbin), "uri", "file:///home/test/test.mp3", NULL); 00033 if (dst_type == "alsasink") 00034 { 00035 _decoder = gst_element_factory_make("decodebin", "decoder"); 00036 g_signal_connect(_decoder, "new-decoded-pad", G_CALLBACK(cb_newpad),this); 00037 gst_bin_add( GST_BIN(_pipeline), _decoder); 00038 gst_element_link(_source, _decoder); 00039 00040 _audio = gst_bin_new("audiobin"); 00041 _convert = gst_element_factory_make("audioconvert", "convert"); 00042 audiopad = gst_element_get_static_pad(_convert, "sink"); 00043 _sink = gst_element_factory_make("alsasink", "sink"); 00044 gst_bin_add_many( GST_BIN(_audio), _convert, _sink, NULL); 00045 gst_element_link(_convert, _sink); 00046 gst_element_add_pad(_audio, gst_ghost_pad_new("sink", audiopad)); 00047 gst_object_unref(audiopad); 00048 00049 gst_bin_add(GST_BIN(_pipeline), _audio); 00050 00051 } 00052 else 00053 { 00054 _sink = gst_element_factory_make("filesink", "sink"); 00055 g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL); 00056 gst_bin_add(GST_BIN(_pipeline), _sink); 00057 gst_element_link(_source, _sink); 00058 } 00059 00060 gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING); 00061 //gst_element_set_state(GST_ELEMENT(_playbin), GST_STATE_PLAYING); 00062 00063 _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) ); 00064 } 00065 00066 private: 00067 00068 void onAudio(const audio_common_msgs::AudioDataConstPtr &msg) 00069 { 00070 GstBuffer *buffer = gst_buffer_new_and_alloc(msg->data.size()); 00071 memcpy(buffer->data, &msg->data[0], msg->data.size()); 00072 00073 GstFlowReturn ret; 00074 00075 g_signal_emit_by_name(_source, "push-buffer", buffer, &ret); 00076 } 00077 00078 static void cb_newpad (GstElement *decodebin, GstPad *pad, 00079 gboolean last, gpointer data) 00080 { 00081 RosGstPlay *client = reinterpret_cast<RosGstPlay*>(data); 00082 00083 GstCaps *caps; 00084 GstStructure *str; 00085 GstPad *audiopad; 00086 00087 /* only link once */ 00088 audiopad = gst_element_get_static_pad (client->_audio, "sink"); 00089 if (GST_PAD_IS_LINKED (audiopad)) 00090 { 00091 g_object_unref (audiopad); 00092 return; 00093 } 00094 00095 /* check media type */ 00096 caps = gst_pad_get_caps (pad); 00097 str = gst_caps_get_structure (caps, 0); 00098 if (!g_strrstr (gst_structure_get_name (str), "audio")) { 00099 gst_caps_unref (caps); 00100 gst_object_unref (audiopad); 00101 return; 00102 } 00103 00104 gst_caps_unref (caps); 00105 00106 /* link'n'play */ 00107 gst_pad_link (pad, audiopad); 00108 00109 g_object_unref (audiopad); 00110 } 00111 00112 ros::NodeHandle _nh; 00113 ros::Subscriber _sub; 00114 boost::thread _gst_thread; 00115 00116 GstElement *_pipeline, *_source, *_sink, *_decoder, *_convert, *_audio; 00117 GstElement *_playbin; 00118 GMainLoop *_loop; 00119 }; 00120 } 00121 00122 00123 int main (int argc, char **argv) 00124 { 00125 ros::init(argc, argv, "audio_play"); 00126 gst_init(&argc, &argv); 00127 00128 audio_transport::RosGstPlay client; 00129 00130 ros::spin(); 00131 }