Skip to content
29 changes: 29 additions & 0 deletions audio_capture/launch/capture_udp.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
<launch>
<!-- arecord -l will show available input devices, use the car number as
the first number and the subdevice number as the second in a string
like hw:1,0 -->
<arg name="device" default=""/>
<arg name="channels" default="1"/>
<arg name="sample_rate" default="16000"/>
<arg name="format" default="mp3"/>
<arg name="ns" default="audio"/>
<arg name="src" default="udpsrc"/>
<arg name="port" default="5603"/>
<arg name="dst" default="appsink"/>
<arg name="depay" default="L16"/>

<group ns="$(arg ns)">
<node name="audio_capture" pkg="audio_capture" type="audio_capture" output="screen">
<param name="bitrate" value="128"/>
<param name="device" value="$(arg device)"/>
<param name="channels" value="$(arg channels)"/>
<param name="sample_rate" value="$(arg sample_rate)"/>
<param name="format" value="$(arg format)"/>
<param name="src" value="$(arg src)"/>
<param name="port" value="$(arg port)"/>
<param name="dst" value="$(arg dst)"/>
<param name="depay" value="$(arg depay)"/>
</node>
</group>

</launch>
82 changes: 62 additions & 20 deletions audio_capture/src/audio_capture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,7 @@ namespace audio_transport
public:
RosGstCapture()
{
_bitrate = 192;

std::string dst_type;
std::string dst_type, source_type;

// Need to encoding or publish raw wave data
ros::param::param<std::string>("~format", _format, "mp3");
Expand All @@ -33,7 +31,7 @@ namespace audio_transport
ros::param::param<std::string>("~dst", dst_type, "appsink");

// The source of the audio
//ros::param::param<std::string>("~src", source_type, "alsasrc");
ros::param::param<std::string>("~src", source_type, "alsasrc");
std::string device;
ros::param::param<std::string>("~device", device, "");

Expand Down Expand Up @@ -63,29 +61,65 @@ namespace audio_transport
g_object_set( G_OBJECT(_sink), "location", dst_type.c_str(), NULL);
}

_source = gst_element_factory_make("alsasrc", "source");
// if device isn't specified, it will use the default which is
// the alsa default source.
// A valid device will be of the foram hw:0,0 with other numbers
// than 0 and 0 as are available.
if (device != "")
{
// ghcar *gst_device = device.c_str();
g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL);
}
_source = gst_element_factory_make(source_type.c_str(), "source");

_filter = gst_element_factory_make("capsfilter", "filter");

GstCaps *caps;
if (source_type == "udpsrc")
{
GstCaps *caps;
int port;
ros::param::param<int>("~port", port, 5603);
g_object_set (G_OBJECT (_source), "port", port, NULL);

std::string depay;
ros::param::param<std::string>("~depay", depay, "L16");

caps = gst_caps_new_simple("application/x-rtp",
"media", G_TYPE_STRING, "audio",
"clock-rate", G_TYPE_INT, _sample_rate,
"encoding-name", G_TYPE_STRING, depay.c_str(),
"channels", G_TYPE_INT, _channels,
NULL);

if (depay == "L16")
{
_depay = gst_element_factory_make ("rtpL16depay", "rtpdepay");
}
else
{
ROS_ERROR_STREAM("Depay currently not supported, it must be \"L16\"");
exitOnMainThread(1);
}
}
else if (source_type == "alsasrc")
{
// if device isn't specified, it will use the default which is
// the alsa default source.
// A valid device will be of the foram hw:0,0 with other numbers
// than 0 and 0 as are available.
if (device != "")
{
// ghcar *gst_device = device.c_str();
g_object_set(G_OBJECT(_source), "device", device.c_str(), NULL);
}

caps = gst_caps_new_simple("audio/x-raw",
// "channels", G_TYPE_INT, _channels,
// "depth", G_TYPE_INT, _depth,
"rate", G_TYPE_INT, _sample_rate,
// "signed", G_TYPE_BOOLEAN, TRUE,
NULL);
g_object_set( G_OBJECT(_filter), "caps", caps, NULL);
gst_caps_unref(caps);

_depay = NULL;
}
else
{
ROS_ERROR_STREAM("Source currently not supported");
exitOnMainThread(1);
}
g_object_set( G_OBJECT(_filter), "caps", caps, NULL);
gst_caps_unref(caps);

_convert = gst_element_factory_make("audioconvert", "convert");
if (!_convert) {
Expand All @@ -104,8 +138,16 @@ namespace audio_transport
g_object_set( G_OBJECT(_encode), "quality", 2.0, NULL);
g_object_set( G_OBJECT(_encode), "bitrate", _bitrate, NULL);

gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _convert, _encode, _sink, NULL);
link_ok = gst_element_link_many(_source, _filter, _convert, _encode, _sink, NULL);
if (_depay== NULL)
{
gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _convert, _encode, _sink, NULL);
link_ok = gst_element_link_many(_source, _filter, _convert, _encode, _sink, NULL);
}
else
{
gst_bin_add_many( GST_BIN(_pipeline), _source, _filter, _depay, _convert, _encode, _sink, NULL);
link_ok = gst_element_link_many(_source, _filter, _depay, _convert, _encode, _sink, NULL);
}
} else if (_format == "wave") {
GstCaps *caps;
caps = gst_caps_new_simple("audio/x-raw",
Expand Down Expand Up @@ -209,7 +251,7 @@ namespace audio_transport

boost::thread _gst_thread;

GstElement *_pipeline, *_source, *_filter, *_sink, *_convert, *_encode;
GstElement *_pipeline, *_source, *_filter, *_sink, *_convert, *_encode, *_depay;
GstBus *_bus;
int _bitrate, _channels, _depth, _sample_rate;
GMainLoop *_loop;
Expand Down