跳到主要内容

AIUI node

Roban 调用讯飞 AIUI 接口实现语音识别、语音合成等功能。节点启动后,AIUI 处于待唤醒状态,使用唤醒词 “鲁班鲁班” 唤醒进入工作状态。当服务端下发结束或等待上传超时时,AIUI 重新进入待唤醒状态等待唤醒。

获取语音唤醒的方位

语音交互的唤醒词是 “鲁班鲁班”,唤醒词的识别是在声卡版上实现的,识别到唤醒词后,会根据六 mic 阵列各个麦克风的拾音情况,计算出发声声源的方位并通过 ros 消息将方位发布出来

语音唤醒消息

  • 消息名

    • /micarrays/wakeup
  • 消息类型

    • std_msgs/String
  • 消息类型定义

    • string data

订阅语音唤醒消息(Python 实现)

#!/usr/local/bin/python
# -*- coding: utf-8 -*-
import rospy
from std_msgs.msg import String # 导入消息类型
import json

class WakeUp():
def __init__(self):
rospy.Subscriber("/micarrays/wakeup", String, self.wakeup_callback)
rospy.spin() # 控制 ROS 系统中的消息循环

def wakeup_callback(self, msg):
data = msg.data # 得到一个字符串,如:{u'key_word': u'lu3', u'score': u'1338', u'angle': u'324'}
data = json.loads(msg.data.replace("'", '"')) # 将字符串里的 ' 转换成 ",便于直接用 json 把字符串转成 dict,得到:{u'key_word': u'lu3', u'score': u'1338', u'angle': u'324'}
angle = float(data['angle']) # 得到 angle 即为声源的角度
rospy.loginfo("声音来自 {}°".format(angle))

if __name__ == "__main__":
rospy.init_node("wakeup")
wakeup = WakeUp()
  • angle 数值的含义

    • 头顶上有六个孔,均放置了一个麦克风。声源在 Roban 的正前方时,angle 的数值为 300,顺时针递增,每个孔位相差 60

语音转文字

AIUI 节点有提供用户语音转文字结果的获取,通过 ros 的消息机制将识别出的文字发布

语音转文字消息

  • 消息名

    • /aiui/nlp
  • 消息类型

    • std_msgs/String
  • 消息类型定义

    • string data

订阅语音转文字消息(Python 实现)

#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from std_msgs.msg import String # 导入消息类型

class S2T():
def __init__(self):
rospy.Subscriber("/aiui/nlp", String, self.nlp_callback)
rospy.spin() # 控制 ROS 系统中的消息循环

def nlp_callback(self, msg):
rospy.loginfo(msg.data) # 用 ros 的 log 输出结果

if __name__ == '__main__':
rospy.init_node("speak_to_text")
s2t = S2T()

文字转语音

AIUI 节点同时提供给用户文字转语音的能力,通过 ros 的服务机制向 AIUI 节点发起请求。AIUI 节点会将请求的文字及参数上传服务端,并播放服务端返回的结果

文字转语音服务

  • 服务名

    • /aiui/text_to_speak_multiple_options
  • 服务类型

    • ros_AIUI_node/textToSpeakMultipleOptions
  • 服务类型定义

    string text         # 待转语音的文字
    string vcn # 发音人(目前只支持 'qige'、'dangdang'、'xiaojuan')
    uint8 speed # 语速( 0-100 )
    uint8 pitch # 语调( 0-100 )
    uint8 volume # 音量( 0-100 )
    ---
    bool is_success # 请求成功标识

请求文字转语音服务

Ubuntu 命令行实现

source ~/robot_ros_application/catkin_ws/devel/setup.bash   # 加载工作空间环境变量
rosservice call /aiui/text_to_speak_multiple_options "{text: '你好,我是鲁班', vcn: 'qige', speed: 50, pitch: 50, volume: 50}"

Python 实现

#!/usr/bin/python
# -*- coding: utf-8 -*-
import rospy
from ros_AIUI_node.srv import textToSpeakMultipleOptions

class T2S():
def __init__(self):
self.tts_param = { # 定义待转文字及合成的参数
'text': '你好,我是鲁班',
'vcn': 'qige',
'speed': 50,
'pitch': 5,
'volume': 20
}

def tts(self):
rospy.wait_for_service("/aiui/text_to_speak_multiple_options", timeout=2) # 等待服务可用。超时时间这里设置为 2s,默认会一直等待,超时会抛出 rospy.ROSException 异常
tts_client = rospy.ServiceProxy("/aiui/text_to_speak_multiple_options", textToSpeakMultipleOptions) # 创建 ros 服务客户端
tts_client(self.tts_param['text'], self.tts_param['vcn'], self.tts_param['speed'], self.tts_param['pitch'], self.tts_param['volume']) # 客户端发起请求,参数与该服务的类型定义一一对应

if __name__ == '__main__':
rospy.init_node("text_to_speak")
t2s = T2S()
t2s.tts()