3 #include <gst/app/gstappsink.h> 4 #include <boost/thread.hpp> 8 #include "audio_common_msgs/AudioData.h" 22 ros::param::param<std::string>(
"~format",
_format,
"mp3");
25 ros::param::param<int>(
"~bitrate",
_bitrate, 192);
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);
33 ros::param::param<std::string>(
"~dst", dst_type,
"appsink");
38 ros::param::param<std::string>(
"~device", device,
"");
42 _loop = g_main_loop_new(NULL,
false);
43 _pipeline = gst_pipeline_new(
"ros_pipeline");
45 gst_bus_add_signal_watch(
_bus);
46 g_signal_connect(
_bus,
"message::error",
51 if (dst_type ==
"appsink")
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",
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);
66 _source = gst_element_factory_make(
"alsasrc",
"source");
74 g_object_set(G_OBJECT(_source),
"device", device.c_str(), NULL);
77 _filter = gst_element_factory_make(
"capsfilter",
"filter");
80 caps = gst_caps_new_simple(
"audio/x-raw",
83 "rate", G_TYPE_INT, _sample_rate,
86 g_object_set( G_OBJECT(_filter),
"caps", caps, NULL);
90 _convert = gst_element_factory_make(
"audioconvert",
"convert");
98 if (_format ==
"mp3"){
99 _encode = gst_element_factory_make(
"lamemp3enc",
"encoder");
104 g_object_set( G_OBJECT(
_encode),
"quality", 2.0, NULL);
105 g_object_set( G_OBJECT(
_encode),
"bitrate", _bitrate, NULL);
109 }
else if (_format ==
"wave") {
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,
119 g_object_set( G_OBJECT(
_sink),
"caps", caps, NULL);
120 gst_caps_unref(caps);
122 link_ok = gst_element_link_many( _source,
_sink, NULL);
144 gst_element_set_state(GST_ELEMENT(
_pipeline), GST_STATE_PLAYING);
146 _gst_thread = boost::thread( boost::bind(g_main_loop_run, _loop) );
151 g_main_loop_quit(
_loop);
152 gst_element_set_state(
_pipeline, GST_STATE_NULL);
154 g_main_loop_unref(
_loop);
162 void publish(
const audio_common_msgs::AudioData &msg )
167 static GstFlowReturn
onNewBuffer (GstAppSink *appsink, gpointer userData)
173 g_signal_emit_by_name(appsink,
"pull-sample", &sample);
175 GstBuffer *buffer = gst_sample_get_buffer(sample);
177 audio_common_msgs::AudioData msg;
178 gst_buffer_map(buffer, &map, GST_MAP_READ);
179 msg.data.resize( map.size );
181 memcpy( &msg.data[0], map.data, map.size );
183 gst_buffer_unmap(buffer, &map);
184 gst_sample_unref(sample);
191 static gboolean
onMessage (GstBus *bus, GstMessage *message, gpointer userData)
197 gst_message_parse_error(message, &err, &debug);
201 g_main_loop_quit(server->
_loop);
220 int main (
int argc,
char **argv)
223 gst_init(&argc, &argv);
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)
void exitOnMainThread(int code)
boost::thread _gst_thread
#define ROS_ERROR_STREAM(args)