audio_play.cpp
Go to the documentation of this file.
1 #include <gst/gst.h>
2 #include <gst/app/gstappsrc.h>
3 #include <ros/ros.h>
4 #include <boost/thread.hpp>
5 
6 #include "audio_common_msgs/AudioData.h"
7 
8 namespace audio_transport
9 {
10  class RosGstPlay
11  {
12  public:
14  {
15  GstPad *audiopad;
16 
17  std::string dst_type;
18  std::string device;
19 
20  // The destination of the audio
21  ros::param::param<std::string>("~dst", dst_type, "alsasink");
22  ros::param::param<std::string>("~device", device, std::string());
23 
24  _sub = _nh.subscribe("audio", 10, &RosGstPlay::onAudio, this);
25 
26  _loop = g_main_loop_new(NULL, false);
27 
28  _pipeline = gst_pipeline_new("app_pipeline");
29  _source = gst_element_factory_make("appsrc", "app_source");
30  g_object_set(G_OBJECT(_source), "do-timestamp", TRUE, NULL);
31  gst_bin_add( GST_BIN(_pipeline), _source);
32 
33  //_playbin = gst_element_factory_make("playbin2", "uri_play");
34  //g_object_set( G_OBJECT(_playbin), "uri", "file:///home/test/test.mp3", NULL);
35  if (dst_type == "alsasink")
36  {
37  _decoder = gst_element_factory_make("decodebin", "decoder");
38  g_signal_connect(_decoder, "pad-added", G_CALLBACK(cb_newpad),this);
39  gst_bin_add( GST_BIN(_pipeline), _decoder);
40  gst_element_link(_source, _decoder);
41 
42  _audio = gst_bin_new("audiobin");
43  _convert = gst_element_factory_make("audioconvert", "convert");
44  audiopad = gst_element_get_static_pad(_convert, "sink");
45  _sink = gst_element_factory_make("autoaudiosink", "sink");
46  if (!device.empty()) {
47  g_object_set(G_OBJECT(_sink), "device", device.c_str(), NULL);
48  }
49  gst_bin_add_many( GST_BIN(_audio), _convert, _sink, NULL);
50  gst_element_link(_convert, _sink);
51  gst_element_add_pad(_audio, gst_ghost_pad_new("sink", audiopad));
52  gst_object_unref(audiopad);
53 
54  gst_bin_add(GST_BIN(_pipeline), _audio);
55  }
56  else
57  {
58  _sink = gst_element_factory_make("filesink", "sink");
59  g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
60  gst_bin_add(GST_BIN(_pipeline), _sink);
61  gst_element_link(_source, _sink);
62  }
63 
64  gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
65  //gst_element_set_state(GST_ELEMENT(_playbin), GST_STATE_PLAYING);
66 
67  _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
68  }
69 
70  private:
71 
72  void onAudio(const audio_common_msgs::AudioDataConstPtr &msg)
73  {
74  GstBuffer *buffer = gst_buffer_new_and_alloc(msg->data.size());
75  gst_buffer_fill(buffer, 0, &msg->data[0], msg->data.size());
76  GstFlowReturn ret;
77 
78  g_signal_emit_by_name(_source, "push-buffer", buffer, &ret);
79  }
80 
81  static void cb_newpad (GstElement *decodebin, GstPad *pad,
82  gpointer data)
83  {
84  RosGstPlay *client = reinterpret_cast<RosGstPlay*>(data);
85 
86  GstCaps *caps;
87  GstStructure *str;
88  GstPad *audiopad;
89 
90  /* only link once */
91  audiopad = gst_element_get_static_pad (client->_audio, "sink");
92  if (GST_PAD_IS_LINKED (audiopad))
93  {
94  g_object_unref (audiopad);
95  return;
96  }
97 
98  /* check media type */
99  caps = gst_pad_query_caps (pad, NULL);
100  str = gst_caps_get_structure (caps, 0);
101  if (!g_strrstr (gst_structure_get_name (str), "audio")) {
102  gst_caps_unref (caps);
103  gst_object_unref (audiopad);
104  return;
105  }
106 
107  gst_caps_unref (caps);
108 
109  /* link'n'play */
110  gst_pad_link (pad, audiopad);
111 
112  g_object_unref (audiopad);
113  }
114 
117  boost::thread _gst_thread;
118 
120  GstElement *_playbin;
121  GMainLoop *_loop;
122  };
123 }
124 
125 
126 int main (int argc, char **argv)
127 {
128  ros::init(argc, argv, "audio_play");
129  gst_init(&argc, &argv);
130 
132 
133  ros::spin();
134 }
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static void cb_newpad(GstElement *decodebin, GstPad *pad, gpointer data)
Definition: audio_play.cpp:81
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin()
int main(int argc, char **argv)
Definition: audio_play.cpp:126
void onAudio(const audio_common_msgs::AudioDataConstPtr &msg)
Definition: audio_play.cpp:72


audio_play
Author(s): Nate Koenig
autogenerated on Tue Mar 26 2019 02:30:55