机器人操作系统ROS—使用麦克风阵列实现声源定位及语音控制

上一次带大家实践视觉建图与导航后,有朋友留言想给机器人增加语音控制功能,本文就带大家一起实现。为了使效果更佳,例如当叫机器人“过来”、“到我这来”等时,需要机器人能找到说话所在的方向,所以我们将采用麦克风阵列。

一、概述

麦克风阵列是由一定数目的声学传感器(一般为麦克风)组成,对声场的空间特性进行采样并处理的系统。其主要作用有声源定位,抑制背景噪声、干扰、混响、回声,信号提取与分离。声源定位是指利用麦克风阵列计算声源距离阵列的角度,基于 TDOA(Time Difference Of Arrival,到达时间差)实现对目标声源的跟踪;信号的提取与分离是指在期望方向上有效地形成一个波束,仅拾取波束内的信号,从而达到同时提取声源和抑制噪声的目的;此外利用麦克风阵列提供的信息基于深度神经网络可实现有效的混响去除,从而极大程度上提升了真实应用场景中语音交互的效果。

二、硬件准备

1.硬件准备

本文将采用科大讯飞出的一款可以屏蔽电子音的板子,支持Linux系统,它采用平面式分布结构,包含 6 个麦克风,可实现 360 度等效拾音,唤醒分辨率为 1 度。可以使用麦克风阵列获取原始和降噪音频,获取唤醒角度,主麦编号。麦克风阵列结构如下图所示,配备的按键和接口如下:

  • USB 口:用于与 PC 或嵌入式设备连接
  • ADFU:用于刷固件(暂不用)
  • 参考信号接口:可用于回声消除
  • 麦克风编号:已标注在麦克风上,分别对应 0-5,如图示红色数字所示
  • LED 灯编号:从 0 号麦克风开始,LED 顺时针编号依次为 0-11,如图示黑色数字所示
  • 麦克风获取的音频类型及唤醒角度定义如下:
    降噪音频:采样率 16khz,16bit,为一通道;
    原始音频:采样率 16khz,32bit,为八通道,其中 1-6 通道对应 6 个麦克风,7-8 是参考信号;
  • 唤醒角度:从 0 号麦克风开始,顺时针依次为 0-359;

因为上位机没有喇叭,所以除了麦克风阵列以外还买了个小喇叭,带降噪输出端口的,可以接到麦克风阵列上,避免喇叭干扰麦克风阵列的收音效果。

2.连线方法

  • 麦克风阵列板的 J1 通过 USB 通信线接上位机的 USB 接口,需要标准 USBtype-A 接口,电压 5V,电流 0.5A,pi4或jetson none都可以,用于音频数据传输和控制信号传输。
  • MIC 阵列板的 J2 通过一根 2pin 的参考信号线接上位机功放后端,即功放到喇叭的 SPK+与 SPK-,用于回声消除参考信号的传输,要求输入参考信号的峰峰值不能超过300mV。

 

三、环境准备

1.下载离线语音SDK

  • 注册讯飞开放平台账号:打开讯飞开放平台网页,网址 https://www.xfyun.cn,注册账号。
  • 创建新应用:选择控制台——我的应用——创建新应用——填好对应资料后提交。
  • 下载Linux SDK:进入刚创建的应用,下载离线命令词识别 linux SDK(我这里使用的聚合SDK下载页生成的Linux平台SDK,同时包含了唤醒、识别、合成等库,下载后解压到~/linux_sdk备用)。

2.配置麦克风阵列库

# 麦克风阵列库
cd ~/catkin_ws/src
git clone git@github.com:yanjingang/xf_mic_asr_offline.git
cd xf_mic_asr_offline
# 拷贝.so动态库
sudo cp lib/x64/*  /usr/lib/
#sudo cp lib/arm64/* /usr/lib/
# 替换APPID为上一部步自己注册的appid
vim config/appid_params.yaml
# 配置 udev 规则
sudo cp xf_mic.rules /etc/udev/rules.d/
sudo service udev restart
# 更新库里的科大迅飞离线语音SDK *.jet文件(这些文件内部与appid绑定了,必须同步替换)
cd ~/linux_sdk
cp bin/msc/res/asr/common.jet ~/catkin_ws/src/xf_mic_asr_offline/config/msc/res/asr/
cp -r bin/msc/res/tts bin/msc/res/ivw bin/msc/res/xtts  ~/catkin_ws/src/xf_mic_asr_offline/config/msc/res/

3.安装声卡和语音播放库

# 安装声卡驱动和语音库
sudo apt-get install libasound2-dev sox mplayer
# 插上麦克风USB口,检查设备是否正常识别
lsusb|grep 10d6:b003

4.测试Linux SDK

# 编译语音识别示例
cd ~/linux_sdk
cd samples/asr_offline_record_sample
sh 64bit_make.sh
# 运行测试
cd ~/linux_sdk/bin
./asr_offline_record_sample

5.测试ROS库

# 修改编译平台配置
vim ~/catkin_ws/src/xf_mic_asr_offline/CMakeLists.txt
  link_directories(
   lib/x64  
   # lib/arm64   
 )

# 编译
cd ~/catkin_ws
rm -rf build devel
catkin_make
source ~/catkin_ws/devel/setup.bash
# 开启语音控制底层、导航、雷达扫描节点
roslaunch xf_mic_asr_offline base.launch
# 开启麦克风阵列初始化节点(启动失败错误码说明:https://shimo.im/sheet/w3yUy39uNKs0J7DT)
roslaunch xf_mic_asr_offline mic_init.launch
# 调整声卡音量
alsamixer
# 通过“你好晓微”唤醒

 

、代码解读

总体代码结构:

本文中用到的代码位置:https://github.com/yanjingang/xf_mic_asr_offline。

1.SDK主控程序voice_control.cpp

通过launch/mic_init.launch启动,负责对接麦克风阵列和SDK,初始化麦克风,并将SDK识别结果通过topic发布给唤醒控制器或指令控制器:

  • /mic/pcm/deno       发布实时音频文件
  • /mic/awake/angle  发布唤醒角度
  • /mic/major_mic     发布唤醒主麦克风
  • voice_flag             发布开机成功标志
  • awake_flag           发布麦克风被唤醒标志(被command_recognition命令控制器监听)
  • voice_words         发布离线命令词识别结果(被command_recognition命令控制器监听用于控制)

同时启动一系列服务:

  • get_offline_recognise_result_srv  离线命令词识别服务(被call_recognition录音控制器调用)
  • set_awake_word_srv  修改唤醒词(被call_recognition录音控制器调用)

*注意:这个节点名默认为xf_asr_offline_node而不是voice_control,如果要改node name,则必须把其他程序中调用本服务的前缀同时修改,例如xf_asr_offline_node/get_offline_recognise_result_srv要改为voice_control/get_offline_recognise_result_srv,否则将会调用失败。

2.录音调用控制器call_recognition.cpp

通过launch/base.launch启动,只负责控制录音的主动休眠(指令控制)和被动休眠(连续10和识别周期里没有识别到命令词后自动休眠,需要再次唤醒)。

监听topic:

  • awake_flag      监听麦克风被唤醒标志,用于命令词识别

请求service:

  • get_offline_recognise_result_srv  当发现麦克风被唤醒时,请求voice_control的离线命令词识别服务。这里只处理主动休眠指令、连续识别失败后的被动休眠和提醒(通过pub到voice_words实现),命令不在这里处理

3.命令控制器command_recognition.cpp

通过launch/base.launch启动,主要负责指令的监听和处理。

监听topic:

  • voice_flag             监听开机成功标志,播放启动语音
  • voice_words         监听离线命令词识别结果,发布对应动作topic,并播放对应反馈语音

发布topic:

  • cmd_vel_flag                     发布移动指令标记(前进/后退/左转/右转/停止/休眠)
  • ori_vel                                发布移动x/z坐标
  • goal_control_flag               发布移动目标点标记
  • /move_base_simple/goal  发布移动目标点x/z坐标(坐标目前通过config/recognition_params.yaml文件配置)

4.底盘运动控制器motion_control.cpp

通过launch/base.launch启动,负责底盘移动控制。

监听topic:

  • cmd_vel_flag        监听移动指令标记(前进/后退/左转/右转/停止/休眠)
  • ori_vel                  监听移动x/z坐标

发布topic:

  • cmd_vel               发送移动指令topic

5.主麦动态切换refresh_mic.cpp

通过launch/base.launch启动,负责在底盘移动过程中,修正主麦方向。

根据声源设置主麦后可以连续指令控制,但带来的问题是,小车是会移动的,主麦方向的变化可能会导致收音效果变差。这个刷新主麦方向的节点,是为了保持小车的相对坐标下的方向,但并不能保持全局方向。如过出现过程中主麦发生偏离,可以通过重新唤醒进行修正。

监听topic:

  • awake_flag、/mic/awake/angle       监听当前主麦唤醒状态和方向
  • /robot_pose_ekf/odom_combined    监听底盘小车姿态里程计方位值,主要是pose.pose.orientation.z/w,计算主麦方向是否发生变化,如发生变化调用xf_asr_offline_node/set_major_mic_srv重新设置主麦方向

6.节点状态反馈node_feedback.cpp

通过launch/base.launch启动,主要负责底盘移动节点指令完成状态的反馈和语音播报。

、功能调试

1.自定义唤醒词

# 自定义和唤醒词
vim ~/catkin_ws/src/xf_mic_asr_offline/include/user_interface.h
    char awake_words[30] = "小猪小猪"; 

# 编译
cd ~/catkin_ws
catkin_make
source ~/catkin_ws/devel/setup.bash

# 运行测试
roslaunch xf_mic_asr_offline base.launch
roslaunch xf_mic_asr_offline mic_init.launch

在距离小车 3 米以内,用自定义的“小猪小猪”来唤醒小车。

如果唤醒成功,系统会同时完成以下动作:

  • 捕获唤醒声源角度并发布 ROS 话题信息
  • 根据角度设定主麦并点亮 LED
  • 启动循环录音识别

2.自定义控制命令词

2.1 识别时机

在上一步唤醒成功后,若用户不发指令,即静音状态下,可观察到主麦方向 LED 灯点亮约 3.5 秒、接着熄灭约 0.3 秒,循环执行。此时灯亮代表在 LED 灯方向的主麦被设定,并且正在录音,灯灭代表正在处理识别信息并输出到终端。

这个库目前使用的是边录音边识别+VAD(Voice Activity Detection)的方式,通过 VAD 来检测音频的前端点和后端点,后端点判定依据是 0.8 秒静音。运行时有三种可能情况:

  • 一是检测不到前端点,即全程静音(用户不讲指令),算法在 3.5 秒内检测不到语音的前端点,会自动判断本次录音结束,输出空结果,重新启动一次录音识别。
  • 二是检测到前端点,但检测不到后端点。即用户在灯亮的情况下,开始讲话输入语音信号,并且一直滔滔不绝中间没有超过 0.8 秒的停顿,这样程序会一直录音,LED 灯一直亮,直到录音时间达到最大值(15 秒),判定超出最大识别时间,灯灭输出识别结果。
  • 三是检测到前端点和后端点,用户在灯亮的情况下开始讲话,程序检测到前端点,待用户说完指令,程序检测到 0.8 秒静音后判断语音指令已说完,接着灯灭输出识别结果。在这种情况下,录音时间根据后端点自适应调整,既能在输入短语音情况下,尽快结束录音反馈结果提高实时性,又能在输入长语音情况下,避免只录音一部分的问题。

发出控制指令时,灯灭的 0.3 秒内会完成识别结果的处理,包括 ROS 端的通信等。有效语音信息被识别后且结果置信度大于预设的阈值(18),则会被视为有效结果,发布ROS 话题信息并打印到终端上。若未进入休眠状态,程序会进入下一次录音识别的循环。

2.2 自定义命令词

命令词配置采用BNF语法,具体详见:语法开发指南,这里不再赘述。

默认语法配置文件放在了config/call.bnf里,我们在这里配置一个自定义的控制指令并进行测试:

#BNF+IAT 1.0 UTF-8;

// 定义语法名称为call
!grammar call;

// 声明action词槽
!slot <action>;

// 定义开始规则,同时声明action词槽
!start <callstart>;

// 词槽定义
<callstart>:(小猪|关闭|打开|开始)<choose>;
<choose>:<action>|<navigation>|<turn>;
<action>:前进|后退|停|过来|休眠|自主建图|导航;
<navigation>:(去|来)(厨房|客厅|沙发|餐桌|主卧|次卧室|厕所)[这儿|这里];
<turn>:(左|右)转;

识别命令词之后的处理在command_recognition.cpp,里,我们添加对应的处理逻辑:

/**************************************************************************
函数功能:离线命令词识别结果sub回调函数
入口参数:命令词字符串  voice_control.cpp等
返回  值:无
**************************************************************************/
void voice_words_callback(const std_msgs::String& msg)
{
	/***指令***/
	string str1 = msg.data.c_str();    //取传入数据

	...
	
	/***********************************
	指令:小车去厨房
	动作:底盘运动控制器失能(导航控制),发布目标点
	***********************************/
	else if(str1 == "小猪去厨房")
	{
		target.pose.position.x = kitchen_position_x;
		target.pose.position.y = kitchen_position_y;
		target.pose.orientation.z = kitchen_orientation_z;
		target.pose.orientation.w =kitchen_orientation_w;
		navigation_auto_pub.publish(target);
	}
	/***********************************
	指令:小猪去客厅
	动作:底盘运动控制器失能(导航控制),发布目标点
	***********************************/
	else if(str1 == "小猪去客厅")
	{
		target.pose.position.x = livingroom_position_x;
		target.pose.position.y = livingroom_position_y;
		target.pose.orientation.z = livingroom_orientation_z;
		target.pose.orientation.w = livingroom_orientation_w;
		navigation_auto_pub.publish(target);
	}
	/***********************************
	指令:小猪来沙发这儿
	动作:底盘运动控制器失能(导航控制),发布目标点
	***********************************/
	else if(str1 == "小猪来沙发这儿")
	{
		target.pose.position.x = sofa_position_x;
		target.pose.position.y = sofa_position_y;
		target.pose.orientation.z = sofa_orientation_z;
		target.pose.orientation.w = sofa_orientation_w;
		navigation_auto_pub.publish(target);
	}

	std_msgs::Int8 cmd_vel_flag_msg;
	cmd_vel_flag_msg.data = 0;
	cmd_vel_flag_pub.publish(cmd_vel_flag_msg);

	std_msgs::Int8 goal_control_flag_msg;
	goal_control_flag_msg.data = 1;
	goal_control_pub.publish(goal_control_flag_msg);
	OTHER = (char*) "/feedback_voice/OK.wav";
	WHOLE = join((head + audio_path),OTHER);
	system(WHOLE);
	cout<<"好的:小车自主导航去往目标点"<<endl;

	...
	
}

/**************************************************************************
函数功能:主函数
入口参数:无
返回  值:无
**************************************************************************/
int main(int argc, char** argv)
{
	...
	n.param<float>("/kitchen_position_x", kitchen_position_x, 1);
	...
}

命令词识别测试:

小猪去厨房、小猪去客厅、小猪来沙发这儿

3.控制ROS硬件

说了那么多都还没有跟底盘联动,我们先把所有的代码和环境在底盘嵌入式系统里重新部署一遍,确保语音控制和底盘移动部分各自都是正常的。

然后接下来我们在base.launch中增加motion_control节点:

<!-- 底盘运动控制器 -->
<node pkg="xf_mic_asr_offline" type="motion_control" name="motion_control" />

控制测试:

# 启动语音处理相关包
roslaunch xf_mic_asr_offline base.launch
# 启动麦克风阵列离线SDK主程序
roslaunch xf_mic_asr_offline mic_init.launch
# 启动底盘base control
roslaunch ros_arduino_python arduino.launch
# 查看节点/topic关系(这里topic有点多,有很多可以优化的地方,我们稍后再进行调整)
rqt_graph

测试基本的控制功能:

# 监听cmd_vel指令
rostopic echo /cmd_vel

# 可以先手动发cmd_vel确定底盘可以正常响应
# rostopic pub /cmd_vel geometry_msgs/Twist -r 1 '{ linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0} }'  # 前进

# “小猪小猪”唤醒麦克风后进行语音控制
# 小猪前进、小猪左转、小猪停

4.自定义目标点

刚才我们使用麦克风直接向底盘发送了移动指令,底盘可以正常响应并移动。我们增加了“小猪去厨房、小猪去客厅、小猪来沙发这儿”等自定义命令词。接下来我们以厨房为例,讲解如何设置目标点的坐标试下导航。

4.1 获取目标点坐标

运行 base.launch 后打开 RVIZ,使用 2D 导航工具 2D Nav Goal 选取厨房的目标点和方向后,终端显示对应的坐标点参数:

$ rostopic echo /move_base_simple/goal
header: 
  seq: 1
  stamp: 
    secs: 1648049216
    nsecs: 764869863
  frame_id: "map"
pose: 
  position: 
    x: 1.08039116859
    y: 0.718764781952
    z: 0.0
  orientation: 
    x: 0.0
    y: 0.0
    z: 0.0342203796212
    w: 0.999414311294
---

我们要设置的坐标点需要取 Position 中的 x 和 y 参数,方向取 Orientation 中的 z 和 w 参数。

4.2 配置目标点

得到目标坐标点后我们在 config/recognition_params.yaml 文件添加厨房的 x.y.z.w 坐标参数设置。

kitchen_position_x: 1.08039116859  #语音导航-厨房坐标
kitchen_position_y: 0.718764781952
kitchen_orientation_z: 0.0342203796212
kitchen_orientation_w: 0.999414311294

4.3 离线命令词识别中的目标点坐标处理

在command_recognition.cpp中加载刚才的配置作为自定义目标点的坐标并在指令处理时作为target坐标。

/* 加载配置参数 */
n.param<float>("/kitchen_position_x", kitchen_position_x, 1);
n.param<float>("/kitchen_position_y", kitchen_position_y, 0);
n.param<float>("/kitchen_orientation_z", kitchen_orientation_z, 0);
n.param<float>("/kitchen_orientation_w", kitchen_orientation_w, 1);

4.4 重启lanuch测试

通过“小猪去厨房”进行自定义位置点导航测试即可。

# 启动语音处理相关包
roslaunch xf_mic_asr_offline base.launch
# 启动麦克风阵列离线SDK主程序
roslaunch xf_mic_asr_offline mic_init.launch

# 启动底盘base control 
roslaunch ros_arduino_python arduino.launch
# 启动camera 
roslaunch robot_vslam camera.launch 
# 如果报Warning: USB events thread - failed to set priority. This might cause loss of data...,是因为没有权限,执行以下命令
#sudo -s
#source /home/work/.bashrc
#roslaunch robot_vslam camera.launch
# 启动rtab并自动定位 
roslaunch robot_vslam rtabmap_rgbd.launch localization:=true
# 启动movebase(纯前向视觉无法后退) 
roslaunch robot_vslam move_base.launch planner:=dwa move_forward_only:=true

# pc端查看
roslaunch robot_vslam rtabmap_rviz.launch
# 语音控制“小猪去厨房”

*注:这里需要注意pi4 USB口电压/电流问题。根据实际测试情况来看,3.7V*2给底盘供电、5V3A给pi4供电,如同时启动麦克风阵列、激光雷达/摄像头、导航、底盘控制模块,并发出去厨房指令,此时所有模块同时处于工作状态下,电机一动,pi4的usb口电压电流就不稳并自动断开又重连,重连后串口名的序号发生变化,导致底盘控制、激光雷达等模块断开并报错。这里的解决思路是给底盘的电压不足,导致底盘移动时借用pi4的电压电流导致usb口异常,可以把底盘供电增加到12V,同时去掉激光雷达试下(定位和绕障能力会受到影响)。一定确保供电接线牢固稳定,不会在移动过程中断电。

当前节点关系:

5.声源定位

这节我们尝试通过“小猪过来”来让底盘根据声源方向探索前进。这个麦克风阵列只识别声源方向,不能识别声源距离,所以暂时先不处理距离,先让它能根据声音方向转向,并前进固定距离,以后有空时再加上人脸识别等来判定要前进的距离。

我们需要先在base.launch中增加refresh_mic节点:

<!-- 刷新主麦方向 -->
<node pkg="xf_mic_asr_offline" type="refresh_mic" name="refresh_mic" />

原理即为监听唤醒主麦角度和轮速数据/odom,当唤醒后,轮速z/w发生变化时,自动计算主麦旋转到哪个角度以及对应的麦克风编号,并调用sdk切换主麦,即可在底盘转向的过程中随时掌握声源方向。

需要注意的是,数字0麦克风方向需要朝小车的正前方安装固定,否则相对与小车正前方的argue角度会不对。

功能验证:

启动方法同上不赘述,启动后先唤醒麦克风阵列并进行目标点导航,确认转向过程中主麦方向可以自动变化并锁定声源方向;之后通过语音控制“小猪看我、小猪过来”即可实现自动朝声源方向转向并前进。

、小结

好了,本文我们实现了通过语音命令控制底盘移动,并实现了自主识别声源的方向,这为后续的功能扩展提供了基础,例如机器人听到有人说话就可以根据方向扭脸面对说话的人,结合人脸识别、图像识别也可以实现人脸或身后的跟随。

当然我们还可以通过语音让机器人自主探索环境建图、固定的多点巡逻、机械臂的抓取物品等,本文限于篇幅原因就先到这里,大家如果对机器人的哪个功能扩展感兴趣,请留言给我,我带大家一起实现~!

 

yan 22.2.27

 

树莓派USB口供电能力

欢迎关注下方“非著名资深码农“公众号进行交流~

发表评论

邮箱地址不会被公开。