9.基于snowboy实现ROS中的语音唤醒
0x00 语音交互系统简介
在前面的课程中介绍了如何使用snowboy来进行唤醒词检测,但是前面的代码都是单独的一个程序。无法与ROS进行结合起来,在本次课程中,我们就依照snowboy的示例代码,来完成在ROS中的唤醒词检测。首先,我们需要先了解整个语音交互系统的流程是什么样的。这样才能清楚语音唤醒在整个流程中的作用。下面通过一个简单的示意图来认识整个语音交互流程:
在卷积神经网络算法(CNN)没有被人们应用在语音识别上时,人机语音交互系统体验还很差劲。但是随着CNN的不断发展,在语音识别这个领域CNN大放异彩。使得语音识别发展突飞猛进,现在的人机语音交互系统体验基本上都是非常好的。当然,这里还有一个领域没有被完全征服,那就是自然语言处理(NLP)。剩下的各语音模块体验我感觉都已经非常好了,我们本次课程只介绍本地唤醒部分,就是如何触发机器进入工作状态。
0x01 语音唤醒实现流程
现在我们来重点关注语音唤醒的实现流程,通过学习前面snowboy的课程,对snowboy的唤醒有了一定的认识。下面通过一个图,来学习如何在ROS中使用snowboy来进行唤醒:
在这里可以看到这里录音模块使用的是audio_capture,这是audio_common中的一个子模块。audio_common软件包是跟音频处理相关的软件包,它包含了audio_capture,用来从麦克风获取音频,并可以将其传输到目标位置并可以播放。audio_play就是可以从audio_capture获取音频数据,并将其输送到本地扬声器进行播放。audio_common_msgs是音频传输时的各种消息格式定义。sound_play软件包是用来播放声音文件,同时还可以进行语音合成,当然这里是合成英文。
我们利用audio_capture节点将录制的音频数据发送到audio_data话题中,在此过程中,我们可以将音频数据进行处理。例如进行数据的降噪,这样在audio_data话题中的数据就是比较干净的音频数据了。snowboy_wakeup_detecotr节点是唤醒检测节点,它需要订阅音频数据流,我们订阅audio_data话题就可以了。该snowboy唤醒检测节点就会实时的提取音频话题中数据进行检测,如果检测到唤醒词,那就会向wakeup_flag话题中发送一条唤醒成功的标志。这样后面的语音处理流程就可以启动了,知道语音系统已被触发唤醒,需要进入语音识别ASR流程了。这里的唤醒成功标志可以自定义,为了简单,这里就发送一个int类型的数字1来表示唤醒成功。当然,用户也可以自定义唤醒消息格式也可以。
0x02 唤醒代码实现
这里我们只介绍代码的ROS实现部分,对于snowboy那部分的唤醒代码,大家可以查看前面的教程来了解唤醒过程。那首先来看一下唤醒的launch文件,代码如下:
1<!--
2Copyright: 2016-2019 wwww.corvin.cn ROS小课堂
3Author: corvin
4Description:
5 该启动文件是snowboy唤醒的启动文件,将启动两个节点分别是arduio_capture,
6 用于从麦克风获取音频数据,并将数据发送到指定的话题上.启动的snowboy_wakeup
7 节点就是订阅麦克风数据,取出后然后进行检查音频数据中是否存在指定的唤醒词.
8 当检测到唤醒词就往指定的话题中发送一条唤醒成功的消息.后续的其他流程,可以
9 订阅该唤醒成功的话题,当发现话题中有指定的唤醒成功消息,就可以得知系统被成
10 功唤醒了,这样就可以进行后续的其他语音处理流程了.
11History:
12 20191009:init this file.
13-->
14<launch>
15 <arg name="namespace" default="voice_system" />
16 <arg name="AUDIO_Topic" default="audio_data" />
17 <arg name="WAKEUP_Topic" default="wakeup_topic" />
18
19 <group ns="$(arg namespace)">
20 <node pkg="audio_capture" type="audio_capture" name="audio_capture" output="screen" required="true">
21 <param name="format" value="wave" />
22 <param name="channels" value="1" />
23 <param name="depth" value="16" />
24 <param name="sample_rate" value="16000" />
25 <remap from="audio" to="$(arg AUDIO_Topic)" />
26 </node>
27
28 <node pkg="snowboy_wakeup" type="wakeup_detector" name="snowboy_wakeup" output="screen" respawn="true">
29 <param name="resource_filename" value="$(find snowboy_wakeup)/resources/common.res" />
30 <param name="model_filename" value="$(find snowboy_wakeup)/resources/snowboy.umdl" />
31 <param name="beep_filename" value="$(find snowboy_wakeup)/resources/ding.wav" />
32 <param name="sensitivity_str" value="0.7" />
33 <param name="audio_gain" value="1.0" />
34 <param name="wakeup_topic" value="$(arg WAKEUP_Topic)" />
35 <param name="audio_topic" value="$(arg AUDIO_Topic)" />
36 </node>
37 </group>
38</launch>
这里需要注意的是在audio_capture节点启动中,那些获取音频数据的格式是不能修改的,分别是format、channels、depth、sample_rate这四个参数。因为这四个参数是按照snowboy唤醒检测引擎需要的音频格式来设置的。修改后会导致snowboy唤醒引擎无法正常从音频数据流中检测唤醒词了,对于remap参数,这里就是做了个topic映射,将原本要发布数据流到audio话题上,这里给重新映射到我们自定义的/voice_system/audio_data话题上。其实这里不用remap映射话题也是可以的,只不过我个人看这个audio话题有点太简单,所以给重新映射了一下。
对于snowboy_wakeup节点,我们这里需要加载的参数稍微有点多,不过从参数名称上我们就可以一目了然知道加载的参数是什么作用了。注意这里订阅的audio话题需要是audio_capture发布出来一样的话题名称才行,不然snowboy就没办法获取到音频数据流了。
下面来看snowboy的唤醒检测节点的代码,如下所示:
1#include <ros/ros.h>
2#include <std_msgs/Int32.h>
3#include <snowboy_wakeup/SnowboyReconfigureConfig.h>
4#include <audio_common_msgs/AudioData.h>
5#include <dynamic_reconfigure/server.h>
6#include <hotword_detector.h>
7#include <wiringPi.h>
8
9#define BTN_PIN 27
10volatile char btn_click = 0;
11
12namespace snowboy_wakeup
13{
14 std::string beep_filename;
15 std::string pre_param = "play -q --multi-threaded ";
16 std::string all_param;
17
18 //! \brief The HotwordDetectorNode class Wraps the C++ 11 Snowboy detector in a ROS node
19 class HotwordDetectorNode
20 {
21 public:
22 HotwordDetectorNode():nh_(""),nh_p_("~")
23 {}
24
25 bool initialize()
26 {
27 std::string resource_filename;
28 if (!nh_p_.getParam("resource_filename", resource_filename))
29 {
30 ROS_ERROR("Mandatory parameter 'common.res' not present on the parameter server");
31 return false;
32 }
33
34 std::string model_filename;
35 if (!nh_p_.getParam("model_filename", model_filename))
36 {
37 ROS_ERROR("Mandatory parameter 'model_filename' not present on the parameter server");
38 return false;
39 }
40
41 if (!nh_p_.getParam("beep_filename", beep_filename))
42 {
43 ROS_WARN("Mandatory parameter 'beep_filename' not present on the parameter server");
44 }
45 all_param = pre_param + beep_filename;
46
47 std::string wakeup_topic;
48 if (!nh_p_.getParam("wakeup_topic", wakeup_topic))
49 {
50 ROS_ERROR("Mandatory parameter 'wakeup_topic' not present on the parameter server");
51 return false;
52 }
53
54 std::string audio_topic;
55 if (!nh_p_.getParam("audio_topic", audio_topic))
56 {
57 ROS_ERROR("Mandatory parameter 'audio_topic' not present on the parameter server");
58 return false;
59 }
60
61 audio_sub_ = nh_.subscribe(audio_topic, 1000, &HotwordDetectorNode::audioCallback, this);
62 hotword_pub_ = nh_.advertise<std_msgs::Int32>(wakeup_topic, 1);
63
64 detector_.initialize(resource_filename.c_str(), model_filename.c_str());
65 dynamic_reconfigure_server_.setCallback(boost::bind(&HotwordDetectorNode::reconfigureCallback, this, _1, _2));
66
67 return true;
68 }
69
70 private:
71 ros::NodeHandle nh_;
72
73 //! \brief nh_p_ Local nodehandle for parameters
74 ros::NodeHandle nh_p_;
75
76 ros::Subscriber audio_sub_;
77 ros::Publisher hotword_pub_;
78
79 //! \brief dynamic_reconfigure_server_ In order to online tune the sensitivity and audio gain
80 dynamic_reconfigure::Server<SnowboyReconfigureConfig> dynamic_reconfigure_server_;
81
82 //! \brief detector_ C++ 11 Wrapped Snowboy detect
83 HotwordDetector detector_;
84
85 //! \brief reconfigureCallback Reconfigure update for sensitiviy and audio level
86 //! \param cfg The updated config
87 void reconfigureCallback(SnowboyReconfigureConfig cfg, uint32_t)
88 {
89 detector_.configure(cfg.sensitivity, cfg.audio_gain);
90 ROS_INFO("SnowboyROS ReConfigured callback init");
91 }
92
93 //! \brief audioCallback Audio stream callback
94 //! \param msg The audo data
95 void audioCallback(const audio_common_msgs::AudioDataConstPtr& msg)
96 {
97 if (msg->data.size() != 0)
98 {
99 if ( msg->data.size() % 2 )
100 {
101 ROS_ERROR("Not an even number of bytes in this message!");
102 }
103
104 int16_t sample_array[msg->data.size()/2];
105 for ( size_t i = 0; i < msg->data.size(); i+=2 )
106 {
107 sample_array[i/2] = ((int16_t) (msg->data[i+1]) << 8) + (int16_t) (msg->data[i]);
108 }
109
110 std_msgs::Int32 hotword_msg;
111 int result = detector_.runDetection( &sample_array[0], msg->data.size()/2);
112 if (result == 1 || btn_click == 1)
113 {
114 btn_click = 0;
115 ROS_INFO("wakeUp detected!");
116 hotword_msg.data = 1;
117 hotword_pub_.publish(hotword_msg);
118 system(all_param.data());
119 }
120 else if (result == -3)
121 {
122 ROS_ERROR("Hotword detector not initialized");
123 }
124 else if (result == -1)
125 {
126 ROS_ERROR("Snowboy error");
127 }
128 }
129 }
130 };
131}
132
133//click btn ISR function
134void btnISR()
135{
136 btn_click = 1;
137}
138
139int main(int argc, char** argv)
140{
141 ros::init(argc, argv, "snowboy_wakeup_node");
142 snowboy_wakeup::HotwordDetectorNode ros_hotword_detector_node;
143
144 wiringPiSetup();
145 pinMode(BTN_PIN, INPUT);
146 pullUpDnControl(BTN_PIN, PUD_UP);
147 wiringPiISR(BTN_PIN, INT_EDGE_RISING, &btnISR);
148
149 if (ros_hotword_detector_node.initialize())
150 {
151 ros::spin();
152 }
153 else
154 {
155 ROS_ERROR("Failed to initialize snowboy_node");
156 return 1;
157 }
158
159 return 0;
160}
在main()函数中,我们看到主要是初始化了一个HotwordDetectorNode对象来进行snowboy唤醒词检测的,因为定义一个对象后,就会自动调用initialize()初始化函数。在该初始化函数中会获取launch文件中配置的各参数,然后初始化好订阅者,用来订阅音频数据。配置好发布者,这样就可以在检测到唤醒词后向唤醒话题中发布唤醒成功的消息。最后就是配置下可以动态更新snowboy唤醒引擎参数的dynamic_reconfigure服务,这样我们就能在不停止程序运行的情况下来动态调整最适合我们的唤醒参数。
这里的检测唤醒词的主要工作就是在audioCallback()音频回调函数中执行的,因为audio_capture节点在不断的把麦克风的声音发布到audio_data话题上。而我们的snowboy唤醒引擎就是订阅的这个话题,那么每当有音频数据接收到snowboy唤醒引擎就要做检测。当detector_.runDetection()返回为1时就表明从音频数据流中检测到唤醒词了。
这里我又新增了一个功能,那就是如果你感觉自己发音不够标准,或者很难唤醒的时候,就可以使用按键来强制唤醒了。我这里就是使用语音板上的按钮来实现的,当检测到按钮被按下后,也会向唤醒话题中发送一条唤醒成功的消息。
0x03 运行代码
当我们看完主要的实现代码后,接下来就可以编译运行了。看看在树莓派上使用ROS来做snowboy唤醒检测的效果如何,如下视频所示:
通过上面视频可以得知,我们启动snowboy唤醒引擎的ros命令如下:
roslaunch snowboy_wakeup snowboy_wakeup.launch
在ros中启动snowboy唤醒引擎后,可以查看到话题和节点列表如下:
接下来可以通过rqt_graph图来查看,这样就更直观的看到节点和话题之间的通信关系了,大家要注意,圆的图形是节点,方的是话题。如下图所示:
上面介绍的是使用snowboy默认的唤醒词,如果大家想替换成自己的唤醒词也是可以的。我们只需要提前录制好自己的唤醒词,然后上传到snowboy来生成pmdl格式的唤醒资源文件。对于想知道如何生成自己的唤醒资源文件的流程可以参考前面的文章,在这里我直接使用已经做好的pmdl文件。我们只需要修改launch文件即可,将其中model_filename参数修改为加载自己的文件名即可。如下图所示:
修改后非常重要的一点就是要使用rqt_reconfigure来动态的调整适合的灵敏度和增益值,一般增益值都是往小了改,灵敏度往小了改。当然具体的唤醒词,还是需要根据实际情况来调整的。启动rqt_reconfigure后界面如下:
0x04 源码下载
本次课程中的所有源码,大家可以去ROS小课堂的代码服务上下载,源码仓库地址如下:
https://code.corvin.cn/corvin_zhang/AIVoiceSystem
下载代码后,可以看到完整的源码组成,如下图所示:
0x05 参考资料
[1]. 4.语音板使用snowboy唤醒引擎. https://www.corvin.cn/1591.html
[2]. 3.语音板的按钮编程. https://www.corvin.cn/1571.html
[3].ROS wrapper for Snowboy hotword detection. https://github.com/tue-robotics/snowboy_ros
[4].audio_common的ROS Wiki网址. http://wiki.ros.org/audio_common
[5].AIVoiceSytem源码仓库地址. https://code.corvin.cn/corvin_zhang/AIVoiceSystem
0x06 问题反馈
大家在按照教程学习过程中有任何问题,可以直接在文章末尾给我留言,或者关注ROS小课堂的官方微信公众号,在公众号中给我发消息反馈问题也行。我基本上每天都会处理公众号中的留言!当然如果你要是顺便给ROS小课堂打个赏,我也会感激不尽的,打赏30块还会被邀请进ROS小课堂的微信群,与更多志同道合的小伙伴一起学习和交流!
[wshop_reward]