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  GstCaps *caps;
17 
18  std::string dst_type;
19  std::string device;
20  bool do_timestamp;
21  std::string format;
22  int channels;
23  int depth;
24  int sample_rate;
25  std::string sample_format;
26 
27  // The destination of the audio
28  ros::param::param<std::string>("~dst", dst_type, "alsasink");
29  ros::param::param<std::string>("~device", device, std::string());
30  ros::param::param<bool>("~do_timestamp", do_timestamp, true);
31  ros::param::param<std::string>("~format", format, "mp3");
32  ros::param::param<int>("~channels", channels, 1);
33  ros::param::param<int>("~depth", depth, 16);
34  ros::param::param<int>("~sample_rate", sample_rate, 16000);
35  ros::param::param<std::string>("~sample_format", sample_format, "S16LE");
36 
37  _sub = _nh.subscribe("audio", 10, &RosGstPlay::onAudio, this);
38 
39  _loop = g_main_loop_new(NULL, false);
40 
41  _pipeline = gst_pipeline_new("app_pipeline");
42  _source = gst_element_factory_make("appsrc", "app_source");
43  g_object_set(G_OBJECT(_source), "do-timestamp", (do_timestamp) ? TRUE : FALSE, NULL);
44 
45  //_playbin = gst_element_factory_make("playbin2", "uri_play");
46  //g_object_set( G_OBJECT(_playbin), "uri", "file:///home/test/test.mp3", NULL);
47  caps = gst_caps_new_simple(
48  "audio/x-raw",
49  "format", G_TYPE_STRING, sample_format.c_str(),
50  "rate", G_TYPE_INT, sample_rate,
51  "channels", G_TYPE_INT, channels,
52  "width", G_TYPE_INT, depth,
53  "depth", G_TYPE_INT, depth,
54  "signed", G_TYPE_BOOLEAN, TRUE,
55  "layout", G_TYPE_STRING, "interleaved",
56  NULL);
57 
58  if (dst_type == "alsasink")
59  {
60  _audio = gst_bin_new("audiobin");
61  _convert = gst_element_factory_make("audioconvert", "convert");
62  audiopad = gst_element_get_static_pad(_convert, "sink");
63  _resample = gst_element_factory_make("audioresample", "resample");
64 
65  _sink = gst_element_factory_make("alsasink", "sink");
66  g_object_set(G_OBJECT(_sink), "sync", FALSE, NULL);
67  if (!device.empty()) {
68  g_object_set(G_OBJECT(_sink), "device", device.c_str(), NULL);
69  }
70  gst_bin_add_many( GST_BIN(_audio), _convert, _resample, _sink, NULL);
71  gst_element_link_many(_convert, _resample, _sink, NULL);
72  gst_element_add_pad(_audio, gst_ghost_pad_new("sink", audiopad));
73  }
74  else
75  {
76  ROS_INFO("file sink to %s", dst_type.c_str());
77  _sink = gst_element_factory_make("filesink", "sink");
78  g_object_set(G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
79  }
80 
81  if (format == "mp3")
82  {
83  if (dst_type == "alsasink")
84  {
85  _decoder = gst_element_factory_make("decodebin", "decoder");
86  g_signal_connect(_decoder, "pad-added", G_CALLBACK(cb_newpad),this);
87 
88  _filter = gst_element_factory_make("capsfilter", "filter");
89  g_object_set( G_OBJECT(_filter), "caps", caps, NULL);
90 
91  gst_bin_add_many(GST_BIN(_pipeline), _source, _decoder, _filter, _audio, NULL);
92  gst_element_link_many(_source, _decoder, _filter, _audio, NULL);
93  gst_object_unref(audiopad);
94  gst_caps_unref(caps);
95  }
96  else
97  {
98  gst_bin_add_many(GST_BIN(_pipeline), _source, _sink, NULL);
99  gst_element_link(_source, _sink);
100  }
101  }
102  else if (format == "wave")
103  {
104  g_object_set( G_OBJECT(_source), "caps", caps, NULL);
105  g_object_set (G_OBJECT (_source), "format", GST_FORMAT_TIME, NULL);
106  if (dst_type == "alsasink")
107  {
108  gst_bin_add_many( GST_BIN(_pipeline), _source, _audio, NULL);
109  gst_element_link_many( _source, _audio, NULL);
110  gst_object_unref(audiopad);
111  }
112  else
113  {
114  _filter = gst_element_factory_make("wavenc", "filter");
115  gst_bin_add_many(GST_BIN(_pipeline), _source, _filter, _sink, NULL);
116  gst_element_link_many( _source, _filter, _sink, NULL);
117  }
118  gst_caps_unref(caps);
119  }
120  else
121  {
122  ROS_ERROR("Unsupported format: %s", format.c_str());
123  }
124 
125  gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
126  //gst_element_set_state(GST_ELEMENT(_playbin), GST_STATE_PLAYING);
127 
128  _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
129  }
130 
131  private:
132 
133  void onAudio(const audio_common_msgs::AudioDataConstPtr &msg)
134  {
135  GstBuffer *buffer = gst_buffer_new_and_alloc(msg->data.size());
136  gst_buffer_fill(buffer, 0, &msg->data[0], msg->data.size());
137  GstFlowReturn ret;
138 
139  g_signal_emit_by_name(_source, "push-buffer", buffer, &ret);
140  }
141 
142  static void cb_newpad (GstElement *decodebin, GstPad *pad,
143  gpointer data)
144  {
145  RosGstPlay *client = reinterpret_cast<RosGstPlay*>(data);
146 
147  GstCaps *caps;
148  GstStructure *str;
149  GstPad *audiopad;
150 
151  /* only link once */
152  audiopad = gst_element_get_static_pad (client->_audio, "sink");
153  if (GST_PAD_IS_LINKED (audiopad))
154  {
155  g_object_unref (audiopad);
156  return;
157  }
158 
159  /* check media type */
160  caps = gst_pad_query_caps (pad, NULL);
161  str = gst_caps_get_structure (caps, 0);
162  if (!g_strrstr (gst_structure_get_name (str), "audio")) {
163  gst_caps_unref (caps);
164  gst_object_unref (audiopad);
165  return;
166  }
167 
168  gst_caps_unref (caps);
169 
170  /* link'n'play */
171  gst_pad_link (pad, audiopad);
172 
173  g_object_unref (audiopad);
174  }
175 
178  boost::thread _gst_thread;
179 
181  GstElement *_playbin;
182  GMainLoop *_loop;
183  };
184 }
185 
186 
187 int main (int argc, char **argv)
188 {
189  ros::init(argc, argv, "audio_play");
190  gst_init(&argc, &argv);
191 
193 
194  ros::spin();
195 }
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:142
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO(...)
ROSCPP_DECL void spin()
int main(int argc, char **argv)
Definition: audio_play.cpp:187
#define ROS_ERROR(...)
void onAudio(const audio_common_msgs::AudioDataConstPtr &msg)
Definition: audio_play.cpp:133


audio_play
Author(s): Nate Koenig
autogenerated on Fri Apr 9 2021 02:41:15