3 #include <gst/app/gstappsink.h> 4 #include <boost/thread.hpp> 8 #include "audio_common_msgs/AudioData.h" 9 #include "audio_common_msgs/AudioInfo.h" 23 ros::param::param<std::string>(
"~format",
_format,
"mp3");
24 ros::param::param<std::string>(
"~sample_format",
_sample_format,
"S16LE");
27 ros::param::param<int>(
"~bitrate",
_bitrate, 192);
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);
35 ros::param::param<std::string>(
"~dst", dst_type,
"appsink");
40 ros::param::param<std::string>(
"~device", device,
"");
45 _loop = g_main_loop_new(NULL,
false);
46 _pipeline = gst_pipeline_new(
"ros_pipeline");
48 gst_bus_add_signal_watch(
_bus);
49 g_signal_connect(
_bus,
"message::error",
54 if (dst_type ==
"appsink")
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",
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);
69 _source = gst_element_factory_make(
"alsasrc",
"source");
77 g_object_set(G_OBJECT(_source),
"device", device.c_str(), NULL);
81 caps = gst_caps_new_simple(
"audio/x-raw",
82 "format", G_TYPE_STRING, _sample_format.c_str(),
84 "width", G_TYPE_INT,
_depth,
85 "depth", G_TYPE_INT,
_depth,
87 "signed", G_TYPE_BOOLEAN, TRUE,
91 if (_format ==
"mp3"){
92 _filter = gst_element_factory_make(
"capsfilter",
"filter");
93 g_object_set( G_OBJECT(
_filter),
"caps", caps, NULL);
96 _convert = gst_element_factory_make(
"audioconvert",
"convert");
102 _encode = gst_element_factory_make(
"lamemp3enc",
"encoder");
107 g_object_set( G_OBJECT(
_encode),
"target", 1, NULL);
108 g_object_set( G_OBJECT(
_encode),
"bitrate", _bitrate, 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);
117 link_ok = gst_element_link_many( _source,
_sink, NULL);
119 _filter = gst_element_factory_make(
"wavenc",
"filter");
121 link_ok = gst_element_link_many( _source,
_filter,
_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) );
148 audio_common_msgs::AudioInfo info_msg;
153 info_msg.coding_format =
_format;
154 _pub_info.publish(info_msg);
159 g_main_loop_quit(
_loop);
160 gst_element_set_state(
_pipeline, GST_STATE_NULL);
162 g_main_loop_unref(
_loop);
170 void publish(
const audio_common_msgs::AudioData &msg )
175 static GstFlowReturn
onNewBuffer (GstAppSink *appsink, gpointer userData)
181 g_signal_emit_by_name(appsink,
"pull-sample", &sample);
183 GstBuffer *buffer = gst_sample_get_buffer(sample);
185 audio_common_msgs::AudioData msg;
186 gst_buffer_map(buffer, &map, GST_MAP_READ);
187 msg.data.resize( map.size );
189 memcpy( &msg.data[0], map.data, map.size );
191 gst_buffer_unmap(buffer, &map);
192 gst_sample_unref(sample);
199 static gboolean
onMessage (GstBus *bus, GstMessage *message, gpointer userData)
205 gst_message_parse_error(message, &err, &debug);
209 g_main_loop_quit(server->
_loop);
229 int main (
int argc,
char **argv)
232 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)
std::string _sample_format
boost::thread _gst_thread
#define ROS_ERROR_STREAM(args)