00001 #include <stdio.h>
00002 #include <gst/gst.h>
00003 #include <gst/app/gstappsink.h>
00004 #include <boost/thread.hpp>
00005
00006 #include <ros/ros.h>
00007
00008 #include "audio_common_msgs/AudioData.h"
00009
00010 namespace audio_transport
00011 {
00012 class RosGstCapture
00013 {
00014 public:
00015 RosGstCapture()
00016 {
00017 _bitrate = 192;
00018
00019 std::string dst_type;
00020 std::string device;
00021
00022
00023 ros::param::param<std::string>("~format", _format, "mp3");
00024
00025
00026 ros::param::param<int>("~bitrate", _bitrate, 192);
00027
00028
00029 ros::param::param<int>("~channels", _channels, 1);
00030 ros::param::param<int>("~depth", _depth, 16);
00031 ros::param::param<int>("~sample_rate", _sample_rate, 16000);
00032
00033
00034 ros::param::param<std::string>("~dst", dst_type, "appsink");
00035
00036
00037
00038 ros::param::param<std::string>("~device", device, std::string());
00039
00040 _pub = _nh.advertise<audio_common_msgs::AudioData>("audio", 10, true);
00041
00042 _loop = g_main_loop_new(NULL, false);
00043 _pipeline = gst_pipeline_new("ros_pipeline");
00044 _bus = gst_pipeline_get_bus(GST_PIPELINE(_pipeline));
00045 gst_bus_add_signal_watch(_bus);
00046 g_signal_connect(_bus, "message::error",
00047 G_CALLBACK(onMessage), this);
00048 g_object_unref(_bus);
00049
00050
00051 if (dst_type == "appsink")
00052 {
00053 _sink = gst_element_factory_make("appsink", "sink");
00054 g_object_set(G_OBJECT(_sink), "emit-signals", true, NULL);
00055 g_object_set(G_OBJECT(_sink), "max-buffers", 100, NULL);
00056 g_signal_connect( G_OBJECT(_sink), "new-buffer",
00057 G_CALLBACK(onNewBuffer), this);
00058 }
00059 else
00060 {
00061 printf("file sink\n");
00062 _sink = gst_element_factory_make("filesink", "sink");
00063 g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
00064 }
00065
00066 _source = gst_element_factory_make("alsasrc", "source");
00067 _convert = gst_element_factory_make("audioconvert", "convert");
00068
00069 if (!device.empty())
00070 {
00071 g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL);
00072 }
00073
00074 gboolean link_ok;
00075
00076 if (_format == "mp3"){
00077 _encode = gst_element_factory_make("lame", "encoder");
00078 g_object_set( G_OBJECT(_encode), "preset", 1001, NULL);
00079 g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL);
00080
00081 gst_bin_add_many( GST_BIN(_pipeline), _source, _convert, _encode, _sink, NULL);
00082 link_ok = gst_element_link_many(_source, _convert, _encode, _sink, NULL);
00083 } else if (_format == "wave") {
00084 GstCaps *caps;
00085 caps = gst_caps_new_simple("audio/x-raw-int",
00086 "channels", G_TYPE_INT, _channels,
00087 "width", G_TYPE_INT, _depth,
00088 "depth", G_TYPE_INT, _depth,
00089 "rate", G_TYPE_INT, _sample_rate,
00090 "signed", G_TYPE_BOOLEAN, TRUE,
00091 NULL);
00092
00093 g_object_set( G_OBJECT(_sink), "caps", caps, NULL);
00094 gst_caps_unref(caps);
00095 gst_bin_add_many( GST_BIN(_pipeline), _source, _sink, NULL);
00096 link_ok = gst_element_link_many( _source, _sink, NULL);
00097 } else {
00098 ROS_ERROR_STREAM("format must be \"wave\" or \"mp3\"");
00099 exitOnMainThread(1);
00100 }
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113 if (!link_ok) {
00114 ROS_ERROR_STREAM("Unsupported media type.");
00115 exitOnMainThread(1);
00116 }
00117
00118 gst_element_set_state(GST_ELEMENT(_pipeline), GST_STATE_PLAYING);
00119
00120 _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
00121 }
00122
00123 ~RosGstCapture()
00124 {
00125 g_main_loop_quit(_loop);
00126 gst_element_set_state(_pipeline, GST_STATE_NULL);
00127 gst_object_unref(_pipeline);
00128 g_main_loop_unref(_loop);
00129 }
00130
00131 void exitOnMainThread(int code)
00132 {
00133 exit(code);
00134 }
00135
00136 void publish( const audio_common_msgs::AudioData &msg )
00137 {
00138 _pub.publish(msg);
00139 }
00140
00141 static GstFlowReturn onNewBuffer (GstAppSink *appsink, gpointer userData)
00142 {
00143 RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
00144
00145 GstBuffer *buffer;
00146 g_signal_emit_by_name(appsink, "pull-buffer", &buffer);
00147
00148 audio_common_msgs::AudioData msg;
00149 msg.data.resize( buffer->size );
00150 memcpy( &msg.data[0], buffer->data, buffer->size);
00151
00152 server->publish(msg);
00153
00154 return GST_FLOW_OK;
00155 }
00156
00157 static gboolean onMessage (GstBus *bus, GstMessage *message, gpointer userData)
00158 {
00159 RosGstCapture *server = reinterpret_cast<RosGstCapture*>(userData);
00160 GError *err;
00161 gchar *debug;
00162
00163 gst_message_parse_error(message, &err, &debug);
00164 ROS_ERROR_STREAM("gstreamer: " << err->message);
00165 g_error_free(err);
00166 g_free(debug);
00167 g_main_loop_quit(server->_loop);
00168 server->exitOnMainThread(1);
00169 return FALSE;
00170 }
00171
00172 private:
00173 ros::NodeHandle _nh;
00174 ros::Publisher _pub;
00175
00176 boost::thread _gst_thread;
00177
00178 GstElement *_pipeline, *_source, *_sink, *_convert, *_encode;
00179 GstBus *_bus;
00180 int _bitrate, _channels, _depth, _sample_rate;
00181 GMainLoop *_loop;
00182 std::string _format;
00183 };
00184 }
00185
00186 int main (int argc, char **argv)
00187 {
00188 ros::init(argc, argv, "audio_capture");
00189 gst_init(&argc, &argv);
00190
00191 audio_transport::RosGstCapture server;
00192 ros::spin();
00193 }