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