在简单理解了上面的相关概念之后,接下来我们将使用 Aquila C++ 开源信号处理库 来完成基于ROS通信框架下的VAD算法。
# ROS 节点设计方案
首先需要清楚的是,ROS既然是分布式通信框架,那么其目的主要是能够让每个节点的任务尽可能的精简。但如何精简,这需要看设计者如何设计,但此次的设计很明朗。既然要对音频信号进行分析,那么咱们可以这样划分:
- 音频捕获
- 预加重
- 加窗分帧
- 特征提取
- VAD检测
对于音频捕获,在上一篇博客之中已经介绍如何使用以 ALSA 挂载的音频设备获取音频数据,若还不清楚建议翻阅。对于预加重和加窗也做了详细的说明,这两个节点的设计也比较简单。可自行尝试,具体实现代码也可通过这里查阅
创建通信桥梁
虽然说每个节点有特定的任务,并且这个任务尽可能简单。但是其它节点如何与该节点保持通信呢?ROS中提供了自定义的消息类型,用起来也比较简单,详细使用已有很多教程,不过建议还是直接查看官网。由于上篇介绍了捕获,并且采用的是以块捕获的一种形式。那么这种消息数据类型该如何确定好。这里需要注意两个关键点:
- ROS消息的接收
- 每个样本的长度(决定是char or short 等)
因为要保存的音频样本长度不确定,所以尽可能选取能容纳更多位的数据类型,如float;这里所说的接收方接收整一块的数据的形式,即C++/Python接收的数据在通信过程中使用的对象分别是:
- C++:Vector 容器
- Python: 元组(好理解,保护数据不被改变)
既然这样,那么干脆就设计一个数组形式的消息就可以了,由于整一个交互系统设计在接下去开发的过程中可能会用到其它自定义消息类型,所以我们就先创建一个专门用来存放消息的包,并且在包中建立自己的消息文件,若其它功能包需要该包的消息文件,那么只需要在其它功能包的 CMakeList.txt 文件中添加消息包依赖即可。
在进入catkin工作空间并创建一个专门用于存放自定义消息的包。由于这个包只是单纯存放消息文件,所以不需要其它依赖包。
catkin_create_pkg audio_msgs std_msgs
之后进入该消息包中,创建 msg 目录并创建自定义消息文件本次创建的消息包 audio_msgs 中建立的消息文件如下:
- AudioData.msg : 原始音频数据
- AudioFeature.msg : 单独特征
- AudioFeatureSet.msg : 组合特征
详细内容可以查看:audio_msgs 消息文件设计
特征提取
消息文件已经确定,并且能够使用音频捕获节点获取信息。那么接下来就是对采集的音频信号进行特征提取。本次只采用过零和能量两种特征,其它特征先不考虑。
再次进入catkin工作空间并创建特征包:
catkin_create_pkg audio_features roscpp rospy std_msgs audio_msgs
这里注意添加刚刚创建的的消息包依赖。好了,下面就可以直接在该包中创建我们自己的代码了。
在进行特征提取之前,需要明确接下去的端点判决说需要的特征。为了在端点判决时比较容易处理,这次特征提取后将不同的特征打包后再通过节点发送。如果后续还需要添加其它特征,那么依据文件来修改会比较简单。具体该如何设计好?要不就设计一个类,方便自己再次扩展。这次的类设计头文件内容如下:
特征类
namespace Hntea {
class FeatureSet: public Aquila::SignalSource
{
public:
FeatureSet();
FeatureSet(const std::vector<int16_t>& source,double frequence);
virtual ~FeatureSet();
/*
* 函数功能:均值统计
* 参数说明:
* 返回值:均值
* */
float mean();
/*
* 函数功能:统计过零率
* 参数说明:
* 返回值:过零率
* */
float zeroCrossing();
/*
* 函数功能:统计对数能量
* 参数说明:
* 返回值:对数能量
* */
float logEnergy();
};
这个类直接继承了信号处理库中的类,设计相对简单,可以直接看出我们这个类到底需要获取什么特征信号。以后想再次拓展其它特征提取,只要修改该实现文件并在自定义消息文件中添加新特征即可。若有兴趣可以跳转到此处查看源码.
我们一直想让每个节点的任务尽可能的简单的原因是,当出现问题时,可以很容易的定位到相应的节点文件中去。那么对于特征节点采集这个节点,有了上面的实现类,下面只需要在节点文件中直接调用并配合消息文件就好了。
特征发布节点设计
/*
* feature_set.cpp
*
* Created on: 2017年2月27日
* Author: hntea
*
* 函数功能:多特征采集
*/
#include <iostream>
#include <vector>
#include "audio_msgs/AudioData.h"
#include "audio_msgs/AudioFeatureSet.h"
#include "ros/ros.h"
#include "FeatureSet.h"
ros::Publisher _pub;
float _frq;
void callback(const audio_msgs::AudioData &msgs)
{
std::vector<int16_t> src(msgs.data);
Hntea::FeatureSet features(src,_frq);
audio_msgs::AudioFeatureSet features_msgs;
features_msgs.logenergy = features.logEnergy();
features_msgs.mean = features.mean();
features_msgs.zerocrossing = features.zeroCrossing();
_pub.publish(features_msgs);
}
int main (int argc, char **argv)
{
ros::init(argc, argv, "feature_set");
if(!ros::param::get("/audio_capture/sample_rate",_frq))
{
_frq = 16000;
}
ros::NodeHandle n;
ros::Subscriber sb = n.subscribe("hamming_window",50,callback);
_pub = n.advertise<audio_msgs::AudioFeatureSet>("audio_feature/feature_set",1000);
ros::spin();
return 0;
}
是不是很简单?只要把ROS的节点模板一套,然后通过我们自定义的消息文件(简单的说就是自定义的数据结构),万事大吉。下面只需要简单的编译,之后运行节点就能够正常发布消息了。不过不能急,还需要进一步确定节点是否能执行正常。运行节点后,最简单的办法直接通过终端输出该节点打印的消息数据:
就像这样:
hntea@HnteaPC:~$ rostopic echo /audio_feature/feature_set
logenergy: 5.33753824234
zerocrossing: 86.0
mean: -0.0234375
---
logenergy: 7.46965408325
zerocrossing: 118.0
mean: -0.02734375
---
或者你可以使用图形显示,直接看波形更加明显:rqt_plot 通过上面的消息可以看出节点很正常,但接下来如何设计判决算法?
VAD算法设计
语音端点检测算法层出不穷,端点检测准确率不断提高。其中大概可以分为两种,一种是基于特征判决的算法,另一种是基于模式匹配的算法。每种算法都有不同的优缺点。针对不同的处理平台,可以根据平台的计算能力选择不同的解决方案。下面简要列举在处理端点信号时所采用的一些方法:
基于特征检测的相关方法
- 能量与过零双阈值算法:应用广泛当抗噪能力差
- 倒普距离( cepstrum ):倒谱对于语音的特征具有很好的表 征, 在强噪声环境下倒谱系数常用来作为端点检测的特征量。
- 频率倒普系数(MFCC):基于人类声音感知模型的特征分析
- 小波分析+能量熵(wavelet energy entropy)等
基于模式匹配检测的相关方法
- 卷积神经网络
- SVM 支持向两机
- 小波分析+神经网络+粒子群算法
- 小波分析(wcv)+SVM+遗传算法等
复杂的算法都是从最简单的开始,既然如此,就简单设计一个基于能量和过零的双阈值算法。在开始算法之前,有必要了解以下特征用途。
能量:可以用于限定声场距离,说话越大声,能量越大
过零:可以用于判定浊音(语音,但对清辅音不敏感),语音具有周期性,因此若有语音出现,则过零会迅速降低。
还有一个特别注意的问题:不同设备采集到的音频信号量化不同,也就是说同一个检测算法无法同时适用于不同的硬件设备。需要再对相关参数进行调整。
启发式双阈值算法
什么是启发式呢?启发式算法可以这样定义:一个基于直观或经验构造的算法,在可接受的花费(指计算时间和空间)下给出待解决组合优化问题每一个实例的一个可行解,该可行解与最优解的偏离程度一般不能被预计。简单的说,它是以一种根据经验或概率来对结果进行估算;这个估算过程需要一种评估策略(自定义的评估表达式),也就是说不同的评估策略会有不同的结果。
算法思想
- 统计长时背景声音中能量的最高均值:记为 HISTORY_Q_EGMAX
- 统计长时背景声音中过零的最低均值:记为 HISTORY_Q_ZCMIN
- 设定能量高保守阈值 HIGHT_EG 与过零高保守阈值 HIGHT_ZC
- 定义能量与过零的低保守阈值动态调整整策略函数,根据调整函数实时调整低阈值
- 前向搜索第一帧高于低能量且低于低过零的帧,该帧为语音起始的初始估计帧
- 在初始估计帧出现后,取接下来连续的几帧(一般取2-4)中分析,若连续几帧的能量都超过高保守阈值且过零低于高保守阈值,则判定初始估计帧为语音的端点;否则再回到4中继续检测
- 当6中的语音端点出现之后,不断检测接下来信号特征,若能量回落到 HISTORY_Q_EGMAX 过零上升到 HISTORY_Q_ZCMIN 以上,则判定为语音结束。
整体的算法步骤就是这样,其中最重要的就是如何定义第四步中的调整函数。调整策略函数对整体的检测性能影响很大,需要好好设计。还有一个问题就是在后端点判决中采用的是统计策略,也就是说后端点出现是属于大概率事件的,但是其时长是随机的,也就是说结束说话后特征符合判决条件可能不是立即出现,这一点需要注意。
算法细节
在步骤1.2中如何获取统计信息呢?其实我们可以再单独设计一个节点,该节点单独订阅特征,然后对特征信息进行统计之后记录到文件中保存即可,说到统计,用脚本可以缩短开发周期。那么用 Python 来处理也很简单。
声明长度为N列表用于缓存特征 N[]
声明两个数组用于存放各个特征的最高点 HISTORY_Q_EGMAX[] 与 HISTORY_Q_ZCMIN[]
def timecallback():
每隔一段时间刷新缓存,时间间隔尽量长
def callback(消息):
if 缓存特征满:
挑选最高点压入 HISTORY_Q_ZCMIN
挑选最低点压入 HISTORY_Q_EGMAX
if 合适的时刻:
统计 HISTORY_Q_ZCMIN 中的均值
统计 HISTORY_Q_EGMAX 中的均值
以一定格式写入文件
退出
主函数:
节点初始化
初始化定时器
spin()
步骤3中高阈值又该如何选取?这也需要统计,不过统计的方法多样。你可以根据你要的拾音距离对这麦克风说话,利用画图工具rqt_plot查看特征的波动范围,适当折中取值即可。有或是你通过手上的麦克风,录制N个样本,然后对这写样本进行特征提取,然后选取你觉得合适的阈值。
步骤4中如何定义阈值调整函数呢?在统计中常用的是均值,标准差,均方差来描述样本的波动程度。那么我们利用其中的某个或多个统计参数来设计自己的调节算式。如下面这种形式:
ZC低阈值 = std::max(高保守,均值 - u*标准差);
调整策略很重要,至于如何设计因人而异。能够达到满意的效果即可。算法就是一个问题解决步骤,步骤清晰,算法实现也不是很难。关键就在细节的处理上。若对详细代码有兴趣,可以直接戳这里传送。