• 欢迎访问开心洋葱网站,在线教程,推荐使用最新版火狐浏览器和Chrome浏览器访问本网站,欢迎加入开心洋葱 QQ群
  • 为方便开心洋葱网用户,开心洋葱官网已经开启复制功能!
  • 欢迎访问开心洋葱网站,手机也能访问哦~欢迎加入开心洋葱多维思维学习平台 QQ群
  • 如果您觉得本站非常有看点,那么赶紧使用Ctrl+D 收藏开心洋葱吧~~~~~~~~~~~~~!
  • 由于近期流量激增,小站的ECS没能经的起亲们的访问,本站依然没有盈利,如果各位看如果觉着文字不错,还请看官给小站打个赏~~~~~~~~~~~~~!

ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航

人工智能 布剪刀石头 2320次浏览 0个评论

前言

上一篇博客:ros机器人编程实践(15.2)- 使用科大讯飞语音控制turtlebot导航 在上一篇博客中我们已经实现了语音控制turtlebot导航,这一节尝试实现turtlebot语音播报。

科大讯飞的语音合成测试

安装教程在这:传送门  

rosrun xfei_asr tts_subscribe_speak
rostopic pub xfwords std_msgs/String "你好,世界!"

  ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航   根据rostopic pub xfwords std_msgs/String "你好,世界!"我们可以看出语音合成节点接收的话题是xfwords,话题的消息类型是String。  

修改语音导航脚本

sudo gedit ~/wanderbot_ws/src/wanderbot/src/voice_contrl.py

 

#!/usr/bin/env python
# -*- coding: UTF-8 -*-
import rospy
import actionlib
import roslib;
import rospy
from std_msgs.msg import String
 
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal

 
waypoints = [  # <1>
    [(1.522, 0.444, 0.0), (0.0, 0.0, -0.519, 0.85)],
    [(-2.0432, -0.439, 0.0), (0.0, 0.0, -0.559, 0.82902)]
]
 
 
def goal_pose(pose):  # <2>
    goal_pose = MoveBaseGoal()
    goal_pose.target_pose.header.frame_id = 'map'
    goal_pose.target_pose.pose.position.x = pose[0][0]
    goal_pose.target_pose.pose.position.y = pose[0][1]
    goal_pose.target_pose.pose.position.z = pose[0][2]
    goal_pose.target_pose.pose.orientation.x = pose[1][0]
    goal_pose.target_pose.pose.orientation.y = pose[1][1]
    goal_pose.target_pose.pose.orientation.z = pose[1][2]
    goal_pose.target_pose.pose.orientation.w = pose[1][3]
 
    return goal_pose

def callback(msg):
	print msg.data
        pub2 = rospy.Publisher('xfwords',String,queue_size = 1)
	if msg.data.find('一') > -1:
            pose = waypoints[0]
            print '主人,准备出发一号站点请系好安全带!'
            pub2.publish('准备出发一号站点请系好安全带!')
            pub2.publish('准备出发一号站点请系好安全带!')
        elif msg.data.find('三') > -1:
            pose = waypoints[1]
            print '主人,准备出发三号站点请系好安全带!'
            pub2.publish('准备出发三号站点请系好安全带!')
            pub2.publish('准备出发三号站点请系好安全带!')
        else:
            return;

        client = actionlib.SimpleActionClient('move_base', MoveBaseAction)  # <3>
        client.wait_for_server()
            
        print("goal:x=%f y=%f"%(pose[0][0],pose[0][1]))
        goal = goal_pose(pose)
        client.send_goal(goal)
        client.wait_for_result()
	if msg.data.find('一') > -1:
            print '主人,一号站点已经到啦!'
            pub2.publish('主人,一号站点已经到啦!')
        elif msg.data.find('三') > -1:
            print '主人,三号站点已经到啦!'
            pub2.publish('主人,三号站点已经到啦!')

 
if __name__ == '__main__':

    rospy.init_node('message_publisher')

    pub=rospy.Publisher('voiceWakeup',String,queue_size = 1)

    rospy.sleep(1)
    pub.publish('wake up')

    sub = rospy.Subscriber('voiceWords', String,callback)
    rospy.spin()

  代码很简单,就不多解释了。然后我们昨天写的持续唤醒脚本有点小问题,他在不停的登出登录,这样很占网络资源,我们修改下成一次登录。(如果你不想改也无所谓)  

sudo gedit ~/wanderbot_ws/src/robot_voice/src/iat_publish.py

  在前面加上登录的标志位:  

int login_flag = 0;//在前面加上登录的标志位

  如图:   ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航   将while(ros::ok())中修改为:  

        // 语音识别唤醒
        if (wakeupFlag){
            ROS_INFO("Wakeup...");
            int ret = MSP_SUCCESS;
            if(login_flag == 0)
	    {
            	const char* login_params = "appid = 5e608f55, work_dir = .";
 

 
            	ret = MSPLogin(NULL, NULL, login_params);
            	if(MSP_SUCCESS != ret){
                	MSPLogout();
                	printf("MSPLogin failed , Error code %d.\n",ret);
            	}else
                {login_flag = 1;}            
            }

            const char* session_begin_params =
                "sub = iat, domain = iat, language = zh_cn, "
                "accent = mandarin, sample_rate = 16000, "
                "result_type = plain, result_encoding = utf8"; 	
    
            printf("Demo recognizing the speech from microphone\n");
            printf("Speak in 10 seconds\n");
 
            demo_mic(session_begin_params);
 
            printf("10 sec passed\n");
        
            wakeupFlag=0;
            //MSPLogout();
        }

  如图:   ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航   大功告成了~

功能测试

启动仿真环境:

roslaunch turtlebot3_gazebo turtlebot3_world.launch

  启动rviz:

roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml

  启动语音检测脚本:

rosrun robot_voice iat_publish

  启动语音合成脚本:

rosrun xfei_asr tts_subscribe_speak

  启动语音控制导航脚本:

rosrun wanderbot voice_contrl.py 

  后面三条rosrun可以改写成launch脚本,省的启动这么多~

cd ~/wanderbot_ws/src/wanderbot
mkdir launch
cd launch
gedit voiceContrlFunc.launch

  voiceContrlFunc.launch文件如下:

<launch>
  <node pkg="robot_voice" type="iat_publish" name="iat_publish"  output="screen">
  </node>
  <node pkg="xfei_asr" type="tts_subscribe_speak" name="tts_subscribe_speak"  output="screen">
  </node>
  <node pkg="wanderbot" type="voice_contrl.py" name="voice_contrl"  output="screen">
  </node>
</launch>

  然后启动语音控制如下即可:   启动仿真环境:

roslaunch turtlebot3_gazebo turtlebot3_world.launch

  启动rviz:

roslaunch turtlebot3_navigation turtlebot3_navigation.launch map_file:=$HOME/map.yaml

  启动导航功能:

roslaunch wanderbot voiceContrlFunc.launch 

  好了,提示消息全在一个终端了:   ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航


开心洋葱 , 版权所有丨如未注明 , 均为原创丨未经授权请勿修改 , 转载请注明ros机器人编程实践(15.3)- 使用科大讯飞语音控制turtlebot导航
喜欢 (1)

您必须 登录 才能发表评论!

加载中……