audio_capture.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 #include <gst/gst.h>
3 #include <gst/app/gstappsink.h>
4 #include <boost/thread.hpp>
5 
6 #include <ros/ros.h>
7 
8 #include "audio_common_msgs/AudioData.h"
9 
10 namespace audio_transport
11 {
13  {
14  public:
16  {
17  _bitrate = 192;
18 
19  std::string dst_type;
20 
21  // Need to encoding or publish raw wave data
22  ros::param::param<std::string>("~format", _format, "mp3");
23 
24  // The bitrate at which to encode the audio
25  ros::param::param<int>("~bitrate", _bitrate, 192);
26 
27  // only available for raw data
28  ros::param::param<int>("~channels", _channels, 1);
29  ros::param::param<int>("~depth", _depth, 16);
30  ros::param::param<int>("~sample_rate", _sample_rate, 16000);
31 
32  // The destination of the audio
33  ros::param::param<std::string>("~dst", dst_type, "appsink");
34 
35  // The source of the audio
36  //ros::param::param<std::string>("~src", source_type, "alsasrc");
37  std::string device;
38  ros::param::param<std::string>("~device", device, "");
39 
40  _pub = _nh.advertise<audio_common_msgs::AudioData>("audio", 10, true);
41 
42  _loop = g_main_loop_new(NULL, false);
43  _pipeline = gst_pipeline_new("ros_pipeline");
44  _bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline));
45  gst_bus_add_signal_watch(_bus);
46  g_signal_connect(_bus, "message::error",
47  G_CALLBACK(onMessage), this);
48  g_object_unref(_bus);
49 
50  // We create the sink first, just for convenience
51  if (dst_type == "appsink")
52  {
53  _sink = gst_element_factory_make("appsink", "sink");
54  g_object_set(G_OBJECT(_sink), "emit-signals", true, NULL);
55  g_object_set(G_OBJECT(_sink), "max-buffers", 100, NULL);
56  g_signal_connect( G_OBJECT(_sink), "new-sample",
57  G_CALLBACK(onNewBuffer), this);
58  }
59  else
60  {
61  printf("file sink\n");
62  _sink = gst_element_factory_make("filesink", "sink");
63  g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
64  }
65 
66  _source = gst_element_factory_make("alsasrc", "source");
67  // if device isn't specified, it will use the default which is
68  // the alsa default source.
69  // A valid device will be of the foram hw:0,0 with other numbers
70  // than 0 and 0 as are available.
71  if (device != "")
72  {
73  // ghcar *gst_device = device.c_str();
74  g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL);
75  }
76 
77  _filter = gst_element_factory_make("capsfilter", "filter");
78  {
79  GstCaps *caps;
80  caps = gst_caps_new_simple("audio/x-raw",
81  // "channels", G_TYPE_INT, _channels,
82  // "depth", G_TYPE_INT, _depth,
83  "rate", G_TYPE_INT, _sample_rate,
84  // "signed", G_TYPE_BOOLEAN, TRUE,
85  NULL);
86  g_object_set( G_OBJECT(_filter), "caps", caps, NULL);
87  gst_caps_unref(caps);
88  }
89 
90  _convert = gst_element_factory_make("audioconvert", "convert");
91  if (!_convert) {
92  ROS_ERROR_STREAM("Failed to create audioconvert element");
94  }
95 
96  gboolean link_ok;
97 
98  if (_format == "mp3"){
99  _encode = gst_element_factory_make("lamemp3enc", "encoder");
100  if (!_encode) {
101  ROS_ERROR_STREAM("Failed to create encoder element");
102  exitOnMainThread(1);
103  }
104  g_object_set( G_OBJECT(_encode), "quality", 2.0, NULL);
105  g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL);
106 
107  gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _convert, _encode, _sink, NULL);
108  link_ok = gst_element_link_many(_source, _filter, _convert, _encode, _sink, NULL);
109  } else if (_format == "wave") {
110  GstCaps *caps;
111  caps = gst_caps_new_simple("audio/x-raw",
112  "channels", G_TYPE_INT, _channels,
113  "width", G_TYPE_INT, _depth,
114  "depth", G_TYPE_INT, _depth,
115  "rate", G_TYPE_INT, _sample_rate,
116  "signed", G_TYPE_BOOLEAN, TRUE,
117  NULL);
118 
119  g_object_set( G_OBJECT(_sink), "caps", caps, NULL);
120  gst_caps_unref(caps);
121  gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL);
122  link_ok = gst_element_link_many( _source, _sink, NULL);
123  } else {
124  ROS_ERROR_STREAM("format must be \"wave\" or \"mp3\"");
125  exitOnMainThread(1);
126  }
127  /*}
128  else
129  {
130  _sleep_time = 10000;
131  _source = gst_element_factory_make("filesrc", "source");
132  g_object_set(G_OBJECT(_source), "location", source_type.c_str(), NULL);
133 
134  gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL);
135  gst_element_link_many(_source, _sink, NULL);
136  }
137  */
138 
139  if (!link_ok) {
140  ROS_ERROR_STREAM("Unsupported media type.");
141  exitOnMainThread(1);
142  }
143 
144  gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
145 
146  _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
147  }
148 
150  {
151  g_main_loop_quit(_loop);
152  gst_element_set_state(_pipeline, GST_STATE_NULL);
153  gst_object_unref(_pipeline);
154  g_main_loop_unref(_loop);
155  }
156 
157  void exitOnMainThread(int code)
158  {
159  exit(code);
160  }
161 
162  void publish( const audio_common_msgs::AudioData &msg )
163  {
164  _pub.publish(msg);
165  }
166 
167  static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData)
168  {
169  RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
170  GstMapInfo map;
171 
172  GstSample *sample;
173  g_signal_emit_by_name(appsink, "pull-sample", &sample);
174 
175  GstBuffer *buffer = gst_sample_get_buffer(sample);
176 
177  audio_common_msgs::AudioData msg;
178  gst_buffer_map(buffer, &map, GST_MAP_READ);
179  msg.data.resize( map.size );
180 
181  memcpy( &msg.data[0], map.data, map.size );
182 
183  gst_buffer_unmap(buffer, &map);
184  gst_sample_unref(sample);
185 
186  server->publish(msg);
187 
188  return GST_FLOW_OK;
189  }
190 
191  static gboolean onMessage (GstBus *bus, GstMessage *message, gpointer userData)
192  {
193  RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
194  GError *err;
195  gchar *debug;
196 
197  gst_message_parse_error(message, &err, &debug);
198  ROS_ERROR_STREAM("gstreamer: " << err->message);
199  g_error_free(err);
200  g_free(debug);
201  g_main_loop_quit(server->_loop);
202  server->exitOnMainThread(1);
203  return FALSE;
204  }
205 
206  private:
209 
210  boost::thread _gst_thread;
211 
213  GstBus *_bus;
215  GMainLoop *_loop;
216  std::string _format;
217  };
218 }
219 
220 int main (int argc, char **argv)
221 {
222  ros::init(argc, argv, "audio_capture");
223  gst_init(&argc, &argv);
224 
226  ros::spin();
227 }
void publish(const boost::shared_ptr< M > &message) const
static gboolean onMessage(GstBus *bus, GstMessage *message, gpointer userData)
void publish(const audio_common_msgs::AudioData &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
static GstFlowReturn onNewBuffer(GstAppSink *appsink, gpointer userData)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
#define ROS_ERROR_STREAM(args)


audio_capture
Author(s): Nate Koenig
autogenerated on Tue Mar 26 2019 02:30:54