ros使用百度UNIT快速搭建机器人对话系统 人机语音交互
2018-01-19 23:30
651 查看
上篇,我们实现了可以使用百度技术语音转文字,文字转语音。
这里深入一层。给出ros下使用百度UNIT快速搭建机器人对话系统的示例
套路上,在开放平台发布应用,都会有ak 和sk。用这两个k来获取与应用通迅用的token
我分两个节点实现功能
一个处理 获取token并发布。
一个等待token并使用它 与unit应用通迅,
这个节点订阅 用户语音转成的文字topic,把文字发送到 unit 然后把返回 的文字 publish到文字转语音节点订阅的主题上。
从而实现了语音到文字,文字查询输入-->baidu_unit-->查询输出文字,文字到语音的交互.
rqtgraph
python
node_token_main.py
node_talk_main.py
人和机器对话,实际上是要把语句转化成某种指令句式
譬如简单的
向右转,向前看,走你!停!
但是人的自然语言的表达,不会向军训似的简洁,同样的指令不同人会有不同表达方式。
虽然现在有各种的机器学习算法,但是机器对自然语言的理解还是很难处理的。
特别是机器对语言的上下文的联系,一些幽默讽刺,弦外之音的理解都是非常困难的。
即使机器学习很厉害,能从海量数据中抽象出人类不能理解的“概念”,但总的说来,海量数据还是太有局限
机器人类对比从根本上的一点就是没有感觉,没有生活常识,没有情感。
如果给机器加各种传感器,全方位的海量数据,加上深度学习,理解能力肯定会提高,甚至会有智慧和情感。
这种高深的问题留给高人去处理吧。
将来的事将来再说。
现阶段百度的工具来解决当下的问题还是很好的,能省时省力。
下面以大众语言解释解释,个人觉得比官方的好理解。
人机对话时机器需要捕捉每句话语的指示和思想(意图)
而表达的意图,总离不开一些关键的词类组合在一起。
例如,“北京天气”,意图是查天气,这是一个典型实例 “北京”属于地点类的词汇 ,“天气”是表达意图的必要关键词
凡是属于 [地点]+"天气"的说法(模型、模板)我们就把它理解为查天气的意图。
这就类似分类,某些词类的组合就是一个新的抽象类别。这个抽象类别就是意图
所以开发者要定义这些类别,并且给这些类别留出空位,用户来填词。
就跟填空题似的,
还是查天气的模板为例
我们定义为 [地点]+天气
[ ]的位置就是一个槽,需要用户去填,词槽的概念可以这样理解。
要让开发者具体实现操作,百度UNIT分了这样几个操作层面
场景
.>技能
...>单元
.....>对话
.....>问答
对话分场景,比如火车站购票、饭店吃饭点菜、在家看电视、读书、听歌等,好吧,我想不出来了
技能就是所在场景能实现的功能,比如火车站购票窗口,能查询、购买、改签、退款这些个都是技能
查询为例: 我想要明天(从北京)到上海的车票。
从这句话我们就能制定出一个模板 [时间]+[出发地]+[目的地]+车票
这时候词槽也有了
单元有两种,分对话单元和问答单元,有词槽的只能是对话模式。因为这个模式能引导用户把空槽填满。
如果少了信息,系统可以有适当的提示。
譬如,
用户:我想要到个车票。
系统:去哪?
用户:上海
系统:是何处出发?
用户:北京
系统:那天?
用户:明天
系统 查询出结果
问答就是针对一个意图设置不同说法,并给出的各种应答语句,可以多种多样,但是是固定的。
对话样本、特征词、对话模板见下面的官方文档
http://ai.baidu.com/tech/unit
unit要发布到云上,进行调用。
https://cloud.baidu.com
UNIT基础名词
UNIT是一个专业的技术平台, 了解一些名词和概念非常有必要。
场景
一个场景对应一个独立完整的对话系统,用来满足您某个具体业务场景的需求。通常按垂类划分(例如,银行信用卡办理场景、电视遥控器场景等)。
技能
某一个方向的对话能力;技能分为自定义技能和预置技能,自定义技能完全由用户配置,预置技能为UNIT提供的通用能力,支持开发者后期干预。
单元
在UNIT里,对话单元用来定义系统在一个具体的对话任务下对用户对话的理解、以及机器人的回应方式,是系统中的最小对话单位。对话任务例如查天气、查询信用卡年费、控制空调温度等。
对话单元
在每个对话单元里,您需要明确出用户对话的目的是什么(即意图)?要达成用户这个目的,需要理解哪些关键信息,或让用户提供哪些筛选条件(即词槽)? 除此之外,还需要告诉对话系统在什么情况下应该用什么来回应用户(即规则和答复)。
问答单元
问答单元,用于圈定某一个范围的问答内容。在每个问答单元里,您需要明确出这类问答内容对应的主题(即意图)
意图
意图表示用户的目的(例如,”北京天气”,意图是查天气)。
词槽
是满足用户意图时的关键信息或限定条件,可以理解为用户需要提供的筛选条件。例如在查询天气时,词槽是地点和时间。
例如:“换到中央台”中的”中央台”就是一个”电视台词槽”,它会一定程度上影响系统对”换台”这个意图的执行。
对话样本
对话样本就是您给对话系统做示范,教它在用户说的具体句子里,该如何理解意图,哪个词是重要信息,对应的词槽是什么。
例如:通过对话样本标注告诉机器人“三亚明天会不会下雨”与“三亚明日会下雨吗”都是询问天气的语句,其中“三亚”是对应城市city这个词槽,“明日”和“明天”都是time词槽。 这样的训练越多,机器人的理解能力便越强,这与在学习语言中的人类孩童的学习方式也是十分相似的。
特征词
特征词通常被用于约束某条对话模板的匹配范围(例如,天气、下雨、热等类别关键词)或提供一定限度的泛化能力(例如,嗯、了、吧等语气词);活用特征词机制可以事半功倍的提高对话模板的精度和覆盖度。 特征词词典:开发者需自行导入词典,用于系统识别特征词。
对话模板
对话模板是您给对话系统按具体语法、句式做出的示范,教它在某一个特定语法、句式中,该如何理解意图,哪个词是重要信息,对应的词槽、特征词是什么。
例如:“[D:sys_loc][D:sys_time]天气如何”,上述标注表示可以将所有满足“[城市]+[时间]+天气如何”这一规则的query解析为WEATHERINFO意图。如“北京今天天气如何?”,“天津明天天气如何”等。其中“[D:sys_loc]”表示所有城市词组成的集合,“[D:sys_time]”表示所有时间描述组成的集合。
问答对
问题与答案的组合,称之为问答对。问答对支持一对一、一对多、多对一和多对多;当某一个问题对中包含多个答案时,答案随机呈现。
问答集
问答集是承载问答对的容器,与问答单元一一对应,您可以批量将问答内容导入问答集,也可以在线编辑。
训练模型
即把场景下所有的配置、标注的对话样本、对话模板等打包提交给系统来训练模型。 模型生效一般需要几分钟时间。
沙盒
每个场景都配有一个沙盒环境,将训练好的模型生效到沙盒环境后,就可以进行效果验证了,同时可接入到您自己的业务系统中使用。您可以生成多个模型版本,但只能选择一个放到沙盒环境中。
这里深入一层。给出ros下使用百度UNIT快速搭建机器人对话系统的示例
套路上,在开放平台发布应用,都会有ak 和sk。用这两个k来获取与应用通迅用的token
我分两个节点实现功能
一个处理 获取token并发布。
一个等待token并使用它 与unit应用通迅,
这个节点订阅 用户语音转成的文字topic,把文字发送到 unit 然后把返回 的文字 publish到文字转语音节点订阅的主题上。
从而实现了语音到文字,文字查询输入-->baidu_unit-->查询输出文字,文字到语音的交互.
rqtgraph
python
node_token_main.py
#!/usr/bin/env python # -*- coding: utf-8 -*- """ Copyright (c) 2017 zaizhizhuang. All rights reserved. This program is free software; you can redistribute it and/or modify. """ import rospy from std_msgs.msg import String import urllib, urllib2, sys import ssl import json class baidu_unit_token_main(): def __init__(self): self.define() self.get_token() #rospy.Subscriber(self.topic , String , self.talker) rospy.spin() def get_token(self): # client_id 为官网获取的AK, client_secret 为官网获取的SK host = 'https://aip.baidubce.com/oauth/2.0/token?grant_type=client_credentials&client_id='+self.baidu_unit_ak+'&client_secret='+self.baidu_unit_sk request = urllib2.Request(host) request.add_header('Content-Type', 'application/json; charset=UTF-8') response = urllib2.urlopen(request) content = response.read() if (content): print(content) #s = json.dumps(data) s1 = json.loads(content) if (s1['access_token']): self.token_string=s1['access_token'] print(self.token_string) rospy.set_param('baidu_unit_token_string', self.token_string) self.say.publish(self.token_string) else: print('get token error!!!') def define(self): self.say=rospy.Publisher('baidu_unit_token_string', String, queue_size=1) if not rospy.has_param('~baidu_unit_ak'): rospy.set_param('~baidu_unit_ak','xxxxxxxxxxxxxxxxx') if not rospy.has_param('~baidu_unit_sk'): rospy.set_param('~baidu_unit_sk','xxxxxxxxxxxxxxxx') if not rospy.has_param('~baidu_unit_ 4000 token_topic'): rospy.set_param('~baidu_unit_token_topic', 'baidu_unit_token_topic') self.baidu_unit_ak=rospy.get_param('~baidu_unit_ak') self.baidu_unit_sk=rospy.get_param('~baidu_unit_sk') #self.topic=rospy.get_param('~baidu_unit_token_topic') def talker(self,data): if data.data=='reset': self.get_token() else: pass if __name__=="__main__": rospy.init_node('baidu_unit_token') rospy.loginfo("initialization baidu_unit token") baidu_unit_token_main() rospy.loginfo("process done and quit")
node_talk_main.py
#!/usr/bin/env python # -*- coding: utf-8 -*- """ Copyright (c) 2017 zaizhizhuang. All rights reserved. This program is free software; you can redistribute it and/or modify. """ import rospy from std_msgs.msg import String import urllib, urllib2, sys import ssl import json import signal import sys from pprint import pprint class baidu_unit_talk_main(): def __init__(self): self.define() rospy.Subscriber(self.token_topic , String , self.set_token) #wait for token... while not self.access_token: rospy.logwarn('get token Retrying ...') rospy.sleep(1.0) self.access_token=rospy.get_param('/baidu_unit_token_string', '') #listen topic rospy.Subscriber(self.listen_topic , String , self.get_say) #zzz test #self.load("今天北京天气怎么样?") rospy.spin() def get_say(self,data): self.load(data.data) def load(self,data): url = 'https://aip.baidubce.com/rpc/2.0/solution/v1/unit_utterance?access_token=' + self.access_token post_data = "{\"scene_id\":"+str(self.scene_id)+",\"query\":\""+str(data)+"\",\"session_id\":\""+str(self.session_id)+"\"}" print(post_data) request = urllib2.Request(url, post_data) request.add_header('Content-Type', 'application/json; charset=UTF-8') #request.add_header('Content-Type', 'application/json') response = urllib2.urlopen(request) content = response.read() if (content): print(content) #s = json.dumps(data) s1 = json.loads(content) #test #pprint(s1) if (s1[u"result"][u"session_id"]): self.session_id=s1[u"result"][u"session_id"] if (s1[u"result"][u"action_list"][0][u"say"]): self.words=s1[u"result"][u"action_list"][0][u"say"] self.say.publish(self.words) print (self.words) def define(self): self.say=rospy.Publisher('speak_string', String, queue_size=1) if not rospy.has_param('~baidu_unit_scene_id'): rospy.set_param('~baidu_unit_scene_id', 'xxxxxx') if not rospy.has_param('~baidu_unit_token_topic'): rospy.set_param('~baidu_unit_token_topic', 'baidu_unit_token_string') if not rospy.has_param('~baidu_unit_listen_topic'): rospy.set_param('~baidu_unit_listen_topic', 'baidu_unit_listen_string') self.token_topic=rospy.get_param('~baidu_unit_token_topic') self.listen_topic=rospy.get_param('~baidu_unit_listen_topic') self.scene_id=rospy.get_param('~baidu_unit_scene_id') self.access_token='' self.session_id='' def set_token(self,data): print(data) if data.data : self.access_token=data.data else: pass def quit(signum, frame): print 'You choose to stop me.' sys.exit(0) if __name__=="__main__": try: signal.signal(signal.SIGINT, quit) signal.signal(signal.SIGTERM, quit) rospy.init_node('baidu_unit_talk') rospy.loginfo("initialization baidu_unit talking") baidu_unit_talk_main() rospy.loginfo("process done and quit") except Exception, exc: print exc
人和机器对话,实际上是要把语句转化成某种指令句式
譬如简单的
向右转,向前看,走你!停!
但是人的自然语言的表达,不会向军训似的简洁,同样的指令不同人会有不同表达方式。
虽然现在有各种的机器学习算法,但是机器对自然语言的理解还是很难处理的。
特别是机器对语言的上下文的联系,一些幽默讽刺,弦外之音的理解都是非常困难的。
即使机器学习很厉害,能从海量数据中抽象出人类不能理解的“概念”,但总的说来,海量数据还是太有局限
机器人类对比从根本上的一点就是没有感觉,没有生活常识,没有情感。
如果给机器加各种传感器,全方位的海量数据,加上深度学习,理解能力肯定会提高,甚至会有智慧和情感。
这种高深的问题留给高人去处理吧。
将来的事将来再说。
现阶段百度的工具来解决当下的问题还是很好的,能省时省力。
下面以大众语言解释解释,个人觉得比官方的好理解。
人机对话时机器需要捕捉每句话语的指示和思想(意图)
而表达的意图,总离不开一些关键的词类组合在一起。
例如,“北京天气”,意图是查天气,这是一个典型实例 “北京”属于地点类的词汇 ,“天气”是表达意图的必要关键词
凡是属于 [地点]+"天气"的说法(模型、模板)我们就把它理解为查天气的意图。
这就类似分类,某些词类的组合就是一个新的抽象类别。这个抽象类别就是意图
所以开发者要定义这些类别,并且给这些类别留出空位,用户来填词。
就跟填空题似的,
还是查天气的模板为例
我们定义为 [地点]+天气
[ ]的位置就是一个槽,需要用户去填,词槽的概念可以这样理解。
要让开发者具体实现操作,百度UNIT分了这样几个操作层面
场景
.>技能
...>单元
.....>对话
.....>问答
对话分场景,比如火车站购票、饭店吃饭点菜、在家看电视、读书、听歌等,好吧,我想不出来了
技能就是所在场景能实现的功能,比如火车站购票窗口,能查询、购买、改签、退款这些个都是技能
查询为例: 我想要明天(从北京)到上海的车票。
从这句话我们就能制定出一个模板 [时间]+[出发地]+[目的地]+车票
这时候词槽也有了
单元有两种,分对话单元和问答单元,有词槽的只能是对话模式。因为这个模式能引导用户把空槽填满。
如果少了信息,系统可以有适当的提示。
譬如,
用户:我想要到个车票。
系统:去哪?
用户:上海
系统:是何处出发?
用户:北京
系统:那天?
用户:明天
系统 查询出结果
问答就是针对一个意图设置不同说法,并给出的各种应答语句,可以多种多样,但是是固定的。
对话样本、特征词、对话模板见下面的官方文档
http://ai.baidu.com/tech/unit
unit要发布到云上,进行调用。
https://cloud.baidu.com
UNIT基础名词
UNIT是一个专业的技术平台, 了解一些名词和概念非常有必要。
场景
一个场景对应一个独立完整的对话系统,用来满足您某个具体业务场景的需求。通常按垂类划分(例如,银行信用卡办理场景、电视遥控器场景等)。
技能
某一个方向的对话能力;技能分为自定义技能和预置技能,自定义技能完全由用户配置,预置技能为UNIT提供的通用能力,支持开发者后期干预。
单元
在UNIT里,对话单元用来定义系统在一个具体的对话任务下对用户对话的理解、以及机器人的回应方式,是系统中的最小对话单位。对话任务例如查天气、查询信用卡年费、控制空调温度等。
对话单元
在每个对话单元里,您需要明确出用户对话的目的是什么(即意图)?要达成用户这个目的,需要理解哪些关键信息,或让用户提供哪些筛选条件(即词槽)? 除此之外,还需要告诉对话系统在什么情况下应该用什么来回应用户(即规则和答复)。
问答单元
问答单元,用于圈定某一个范围的问答内容。在每个问答单元里,您需要明确出这类问答内容对应的主题(即意图)
意图
意图表示用户的目的(例如,”北京天气”,意图是查天气)。
词槽
是满足用户意图时的关键信息或限定条件,可以理解为用户需要提供的筛选条件。例如在查询天气时,词槽是地点和时间。
例如:“换到中央台”中的”中央台”就是一个”电视台词槽”,它会一定程度上影响系统对”换台”这个意图的执行。
对话样本
对话样本就是您给对话系统做示范,教它在用户说的具体句子里,该如何理解意图,哪个词是重要信息,对应的词槽是什么。
例如:通过对话样本标注告诉机器人“三亚明天会不会下雨”与“三亚明日会下雨吗”都是询问天气的语句,其中“三亚”是对应城市city这个词槽,“明日”和“明天”都是time词槽。 这样的训练越多,机器人的理解能力便越强,这与在学习语言中的人类孩童的学习方式也是十分相似的。
特征词
特征词通常被用于约束某条对话模板的匹配范围(例如,天气、下雨、热等类别关键词)或提供一定限度的泛化能力(例如,嗯、了、吧等语气词);活用特征词机制可以事半功倍的提高对话模板的精度和覆盖度。 特征词词典:开发者需自行导入词典,用于系统识别特征词。
对话模板
对话模板是您给对话系统按具体语法、句式做出的示范,教它在某一个特定语法、句式中,该如何理解意图,哪个词是重要信息,对应的词槽、特征词是什么。
例如:“[D:sys_loc][D:sys_time]天气如何”,上述标注表示可以将所有满足“[城市]+[时间]+天气如何”这一规则的query解析为WEATHERINFO意图。如“北京今天天气如何?”,“天津明天天气如何”等。其中“[D:sys_loc]”表示所有城市词组成的集合,“[D:sys_time]”表示所有时间描述组成的集合。
问答对
问题与答案的组合,称之为问答对。问答对支持一对一、一对多、多对一和多对多;当某一个问题对中包含多个答案时,答案随机呈现。
问答集
问答集是承载问答对的容器,与问答单元一一对应,您可以批量将问答内容导入问答集,也可以在线编辑。
训练模型
即把场景下所有的配置、标注的对话样本、对话模板等打包提交给系统来训练模型。 模型生效一般需要几分钟时间。
沙盒
每个场景都配有一个沙盒环境,将训练好的模型生效到沙盒环境后,就可以进行效果验证了,同时可接入到您自己的业务系统中使用。您可以生成多个模型版本,但只能选择一个放到沙盒环境中。
相关文章推荐
- 在ROS(indigo)中读取手机GPS用于机器人定位~GPS2BT在ubuntu和window系统下的使用方法~
- 使用ASP.NET MVC+Entity Framework快速搭建博客系统——目录
- ROS机器人Diego 1#制作(九)视觉系统之使用Xtion发布点云数据
- ROS机器人Diego 1#制作(七)ROS语音系统
- 在树莓派开发板上进行ROS开发+语音交互系统设计
- 使用redis快速搭建发布-订阅系统(python3x)
- 使用Consul快速搭建简易分布式服务监控系统
- 在Ubuntu系统基于ROS使用废旧Android手机摄像头搭建监控设备
- ROS语音交互(三)科大讯飞语音在ROS平台下使用
- 如何利用ROS MoveIt快速搭建机器人运动规划平台?
- 如何利用ROS MoveIt快速搭建机器人运动规划平台?
- centos系统使用yum快速搭建lamp环境
- 百度 UNIT 技术负责人揭秘:如何让你的对话系统更智能
- 机器人程序设计课程配套系统镜像使用说明( Ubuntu 14.04.5 + ROS indigo )
- AndroidUiAutomator使用Jenkins搭建持续集成测试系统Ⅰ—Android UiAutomator以及快速编译方法
- 人机智能交互技术(ROS-HRI-人与机器人的智能交互)课程介绍与资料
- 在ROS(indigo)中读取手机GPS用于机器人定位~GPS2BT在ubuntu和window系统下的使用方法~
- 使用JPress快速搭建系统
- 在ROS(indigo)中读取手机GPS用于机器人定位~GPS2BT在ubuntu和window系统下的使用方法~
- ROS机器人Diego 1#制作(八)ROS语音系统之整合讯飞语音