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 #include "audio_common_msgs/AudioInfo.h"
10 
11 namespace audio_transport
12 {
14  {
15  public:
17  {
18  _bitrate = 192;
19 
20  std::string dst_type;
21 
22  // Need to encoding or publish raw wave data
23  ros::param::param<std::string>("~format", _format, "mp3");
24  ros::param::param<std::string>("~sample_format", _sample_format, "S16LE");
25 
26  // The bitrate at which to encode the audio
27  ros::param::param<int>("~bitrate", _bitrate, 192);
28 
29  // only available for raw data
30  ros::param::param<int>("~channels", _channels, 1);
31  ros::param::param<int>("~depth", _depth, 16);
32  ros::param::param<int>("~sample_rate", _sample_rate, 16000);
33 
34  // The destination of the audio
35  ros::param::param<std::string>("~dst", dst_type, "appsink");
36 
37  // The source of the audio
38  //ros::param::param<std::string>("~src", source_type, "alsasrc");
39  std::string device;
40  ros::param::param<std::string>("~device", device, "");
41 
42  _pub = _nh.advertise<audio_common_msgs::AudioData>("audio", 10, true);
43  _pub_info = _nh.advertise<audio_common_msgs::AudioInfo>("audio_info", 1, true);
44 
45  _loop = g_main_loop_new(NULL, false);
46  _pipeline = gst_pipeline_new("ros_pipeline");
47  _bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline));
48  gst_bus_add_signal_watch(_bus);
49  g_signal_connect(_bus, "message::error",
50  G_CALLBACK(onMessage), this);
51  g_object_unref(_bus);
52 
53  // We create the sink first, just for convenience
54  if (dst_type == "appsink")
55  {
56  _sink = gst_element_factory_make("appsink", "sink");
57  g_object_set(G_OBJECT(_sink), "emit-signals", true, NULL);
58  g_object_set(G_OBJECT(_sink), "max-buffers", 100, NULL);
59  g_signal_connect( G_OBJECT(_sink), "new-sample",
60  G_CALLBACK(onNewBuffer), this);
61  }
62  else
63  {
64  ROS_INFO("file sink to %s", dst_type.c_str());
65  _sink = gst_element_factory_make("filesink", "sink");
66  g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
67  }
68 
69  _source = gst_element_factory_make("alsasrc", "source");
70  // if device isn't specified, it will use the default which is
71  // the alsa default source.
72  // A valid device will be of the foram hw:0,0 with other numbers
73  // than 0 and 0 as are available.
74  if (device != "")
75  {
76  // ghcar *gst_device = device.c_str();
77  g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL);
78  }
79 
80  GstCaps *caps;
81  caps = gst_caps_new_simple("audio/x-raw",
82  "format", G_TYPE_STRING, _sample_format.c_str(),
83  "channels", G_TYPE_INT, _channels,
84  "width", G_TYPE_INT, _depth,
85  "depth", G_TYPE_INT, _depth,
86  "rate", G_TYPE_INT, _sample_rate,
87  "signed", G_TYPE_BOOLEAN, TRUE,
88  NULL);
89 
90  gboolean link_ok;
91  if (_format == "mp3"){
92  _filter = gst_element_factory_make("capsfilter", "filter");
93  g_object_set( G_OBJECT(_filter), "caps", caps, NULL);
94  gst_caps_unref(caps);
95 
96  _convert = gst_element_factory_make("audioconvert", "convert");
97  if (!_convert) {
98  ROS_ERROR_STREAM("Failed to create audioconvert element");
100  }
101 
102  _encode = gst_element_factory_make("lamemp3enc", "encoder");
103  if (!_encode) {
104  ROS_ERROR_STREAM("Failed to create encoder element");
105  exitOnMainThread(1);
106  }
107  g_object_set( G_OBJECT(_encode), "target", 1, NULL);
108  g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL);
109 
110  gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _convert, _encode, _sink, NULL);
111  link_ok = gst_element_link_many(_source, _filter, _convert, _encode, _sink, NULL);
112  } else if (_format == "wave") {
113  if (dst_type == "appsink") {
114  g_object_set( G_OBJECT(_sink), "caps", caps, NULL);
115  gst_caps_unref(caps);
116  gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL);
117  link_ok = gst_element_link_many( _source, _sink, NULL);
118  } else {
119  _filter = gst_element_factory_make("wavenc", "filter");
120  gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _sink, NULL);
121  link_ok = gst_element_link_many( _source, _filter, _sink, NULL);
122  }
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  audio_common_msgs::AudioInfo info_msg;
149  info_msg.channels = _channels;
150  info_msg.sample_rate = _sample_rate;
151  info_msg.sample_format = _sample_format;
152  info_msg.bitrate = _bitrate;
153  info_msg.coding_format = _format;
154  _pub_info.publish(info_msg);
155  }
156 
158  {
159  g_main_loop_quit(_loop);
160  gst_element_set_state(_pipeline, GST_STATE_NULL);
161  gst_object_unref(_pipeline);
162  g_main_loop_unref(_loop);
163  }
164 
165  void exitOnMainThread(int code)
166  {
167  exit(code);
168  }
169 
170  void publish( const audio_common_msgs::AudioData &msg )
171  {
172  _pub.publish(msg);
173  }
174 
175  static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData)
176  {
177  RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
178  GstMapInfo map;
179 
180  GstSample *sample;
181  g_signal_emit_by_name(appsink, "pull-sample", &sample);
182 
183  GstBuffer *buffer = gst_sample_get_buffer(sample);
184 
185  audio_common_msgs::AudioData msg;
186  gst_buffer_map(buffer, &map, GST_MAP_READ);
187  msg.data.resize( map.size );
188 
189  memcpy( &msg.data[0], map.data, map.size );
190 
191  gst_buffer_unmap(buffer, &map);
192  gst_sample_unref(sample);
193 
194  server->publish(msg);
195 
196  return GST_FLOW_OK;
197  }
198 
199  static gboolean onMessage (GstBus *bus, GstMessage *message, gpointer userData)
200  {
201  RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
202  GError *err;
203  gchar *debug;
204 
205  gst_message_parse_error(message, &err, &debug);
206  ROS_ERROR_STREAM("gstreamer: " << err->message);
207  g_error_free(err);
208  g_free(debug);
209  g_main_loop_quit(server->_loop);
210  server->exitOnMainThread(1);
211  return FALSE;
212  }
213 
214  private:
218 
219  boost::thread _gst_thread;
220 
222  GstBus *_bus;
224  GMainLoop *_loop;
225  std::string _format, _sample_format;
226  };
227 }
228 
229 int main (int argc, char **argv)
230 {
231  ros::init(argc, argv, "audio_capture");
232  gst_init(&argc, &argv);
233 
235  ros::spin();
236 }
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)
#define ROS_INFO(...)
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 Fri Apr 9 2021 02:41:14