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
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
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
74 ros::NodeHandle nh_p_;
75
76 ros::Subscriber audio_sub_;
77 ros::Publisher hotword_pub_;
78
79
80 dynamic_reconfigure::Server<SnowboyReconfigureConfig> dynamic_reconfigure_server_;
81
82
83 HotwordDetector detector_;
84
85
86
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
94
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
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後界面如下:
本次課程中的所有源碼,大家可以去ROS小課堂的代碼服務上下載,源碼倉庫地址如下:
https://code.corvin.cn/corvin_zhang/AIVoiceSystem下載代碼後,可以看到完整的源碼組成,如下圖所示:
0x05 參考資料大家在按照教程學習過程中有任何問題,可以直接在文章末尾給我留言,或者關注ROS小課堂的官方微信公眾號,在公眾號中給我發消息反饋問題也行。我基本上每天都會處理公眾號中的留言!當然如果你要是順便給ROS小課堂打個賞,我也會感激不盡的,打賞30塊還會被邀請進ROS小課堂的微信群,與更多志同道合的小夥伴一起學習和交流!