语音导航

通过前面的课程讲解,我们已经理解了整个实现语音自定义交互的过程。

接下来我们将学习如何通过语音交互功能来控制我们的机器人实现导航功能。而我们的语音导航也是基于前面讲解的自定义交互模式设计的一种功能实现。

1 整体效果

运行默认demo后,我们可以通过语音来向机器人下达前往指定点位的指令,从而实现让机器人自主导航到指定点位的效果。


2 实现过程

2.1 仿真使用

  • 首先我们得通过唤醒词小道小道将机器人唤醒,让其进入唤醒状态。

  • 故我们的前面讲解的 语音离线命令词检测VAD检测节点 需要先行启动:

roslaunch handsfree_speech offline_interactive_ros.launch//语音交互功能节点
rosrun handsfree_speech vad_record.py//VAD检测节点
  • 然后运行 语音导航节点:
rosrun handsfree_speech set_goal.py//语音导航节点
  • 根据语音教程第一节的内容,我们可以先使用仿真环境进行测试来查看一下语音交互的效果在这里我们也提供了相应的仿真环境:
roslaunch handsfree_2dnav navigation.launch

这两个都是仿真环境,在空间不够空旷的情况下或者还没熟练的情况下,执行上面两条命令中,任意一条指令即能进行仿真测试。

通过仿真环境,我们可以用语音交互的功能查看执行效果,并进行语音功能的相关调试。

2.2 实机使用

我们在对语音功能熟悉了之后,便可以开始让机器人进行实际环境的调试。

  • 首先还是启动我们的 语音交互节点VAD检测节点:
roslaunch handsfree_speech offline_interactive_ros.launch//语音交互功能节点

rosrun handsfree_speech vad_record.py//vad检测节点
  • 然后运行 一键导航节点(my_map为先前雷达建图教程中所创建的地图名称):
 roslaunch handsfree_2dnav navigation.launch map_name:=my_map

这个启动命令会启动底盘驱动节点激光雷达节点move_base导航节点以及rviz可视化节点

  • 初始位置的标定:我们可以通过RVIZ可视化工具上方工具栏中的2D Pose Estimate来标定初始化位置,直到机器人在地图中的位置和机器人实际的位置一样。

  • 启动语音导航节点

rosrun handsfree_speech set_goal.py//语音导航节点

一切就绪后,您就可以尝试语音导航功能的使用了。

2.3 控制核心

 if(todo_id==10007&&ifwake==1)
  {
      const char* text ="收到指令,正在前往A点"; //合成文本
      ret =text_to_speech(text, filename_move, session_begin_params);
      if (MSP_SUCCESS != ret)
      {
        printf("text_to_speech failed, error code: %d.\n", ret);
      }
      printf("合成完毕\n");
      printf("收到前往A点指令\n");
      play_wav((char*)filename_move);
      ifwake=0;
      std_msgs::String msg_pub;
      msg_pub.data ="A";
      pub.publish(msg_pub);
  }
        self.pose_x = rospy.get_param('~goal_pose_x',0.0)
        self.pose_y = rospy.get_param('~goal_pose_y',0.0)
        self.pose_z = rospy.get_param('~goal_pose_z',0.0)

        self.quat_x = rospy.get_param('~goal_quat_x',0.0)
        self.quat_y = rospy.get_param('~goal_quat_y',0.0)
        self.quat_z = rospy.get_param('~goal_quat_z',0.0)
        self.quat_w = rospy.get_param('~goal_quat_w',1.0)

        self.goal_finish = 0
        self.shutdown_finish = 0
        rospy.on_shutdown(self.shutdown)

        rospy.Subscriber('/recognizer/output', String, self.speech_callback)
        # Subscribe to the move_base action server
        self.move_base = actionlib.SimpleActionClient("move_base", MoveBaseAction)
        rospy.loginfo("Waiting for move_base action server...")
        # Wait 60 seconds for the action server to become available
        self.move_base.wait_for_server()
        rospy.loginfo("Connected to move base server")
        rospy.loginfo("Starting navigation test")
        rate = rospy.Rate(10) 
        while 1 :
            if self.goal_finish == 1 :
                self.pose_x = rospy.get_param('~goal_pose_x',0.0)
                self.pose_y = rospy.get_param('~goal_pose_y',0.0)
                self.pose_z = rospy.get_param('~goal_pose_z',0.0)

                self.quat_x = rospy.get_param('~goal_quat_x',0.0)
                self.quat_y = rospy.get_param('~goal_quat_y',0.0)
                self.quat_z = rospy.get_param('~goal_quat_z',0.0)
                self.quat_w = rospy.get_param('~goal_quat_w',1.0)
            elif self.shutdown_finish == 1 : #这个是一个程序退出的检测,如果
                break
            rate.sleep()

导航的中断停止处理: 相比于传统的导航程序,我们语音交互的导航程序更加讲究实时性,所以我们要设置一下语音的状态处理。

即当机器人接收到所设置的导航目标点信息时,机器人就会往目标点前进,而如果中途接收到唤醒指令,机器人就会中断当前正在执行的任务,停止运动并等待新的语音指令。

rospy.loginfo(msg)
        if msg.data == 'A':
            self.pose_x = rospy.get_param('~goal_pose_x',11.3)
            self.pose_y = rospy.get_param('~goal_pose_y',50.1)
            self.pose_z = rospy.get_param('~goal_pose_z',0.0)

            self.quat_x = rospy.get_param('~goal_quat_x',0.0)
            self.quat_y = rospy.get_param('~goal_quat_y',0.0)
            self.quat_z = rospy.get_param('~goal_quat_z',0.0)
            self.quat_w = rospy.get_param('~goal_quat_w',1.0)

        elif msg.data == 'shutdown':
            self.shutdown_finish=1
        elif msg.data == 'patrol':
             a=0  #这两个是和巡逻指令配合的适配,如果在同时执行导航功能时,发布巡逻任务的时候不会走导航的原点休息。
        elif msg.data == 'stoppatrol':
             a=0  #这两个是和巡逻指令配合的适配,如果在同时执行导航功能时,发布巡逻任务的时候不会走导航的原点休息。
        else:
            self.pose_x = rospy.get_param('~goal_pose_x',0.0)
            self.pose_y = rospy.get_param('~goal_pose_y',0.0)
            self.pose_z = rospy.get_param('~goal_pose_z',0.0)

            self.quat_x = rospy.get_param('~goal_quat_x',0.0)
            self.quat_y = rospy.get_param('~goal_quat_y',0.0)
            self.quat_z = rospy.get_param('~goal_quat_z',0.0)
            self.quat_w = rospy.get_param('~goal_quat_w',1.0)

        self.goal_finish = 0
    rospy.loginfo('Moving the base through velocity commands')
        goal = MoveBaseGoal()
        goal.target_pose.header.frame_id = 'map'
        goal.target_pose.header.stamp = rospy.Time.now()

        quaternion = Quaternion()
        quaternion.x = self.quat_x
        quaternion.y = self.quat_y
        quaternion.z = self.quat_z
        quaternion.w = self.quat_w
        goal.target_pose.pose.position.x = self.pose_x 
        goal.target_pose.pose.position.y = self.pose_y
        goal.target_pose.pose.position.z = self.pose_z 
        goal.target_pose.pose.orientation = quaternion

        self.move_base.send_goal(goal,self.donecb,self.activecb,self.feedbackcb)

Alt text

2.3.1 初始位置的标定

  • 我们在RVIZ地图中看到的机器人初始位置可能并不是其在现实环境中的实际位置,而为了机器人能正常实现导航,我们需要手动标定初始位置。

  • 点击RVIZ菜单栏的2D Pose Estimate图标。

  • 将鼠标移动到机器人在地图中的实际位置,摁住左键,调整好方向后松开。

  • 重复以上动作,直到机器人在地图中的位置和机器人实际的位置一样。我们可以通过观察激光雷达所扫描的数据和地图的边界是不是吻合来判断机器人的位置标定是否成功。

2.3.2 在仿真情况下,我们是不需要进行实际位置的校准。

仿真环境下,初始化位置就已经是准确的,且机器人仿真雷达数据和地图边界也是吻合的。如果您进行了位置校准,反而会出现位置信息不准确,从而出现导航失败等问题。

标定好的效果如下: Alt text

为了能让机器人导航到我们设置的目标点,我们还需要修改相应代码中的坐标点参数,将其设置为目标点位的参数。

修改步骤如下:

  • 首先,我们得根据雷达建图教程来创建一个实际环境的地图。 然后通过rviz可视化工具打开该地图,并通过rviz上方工具栏的 Publish Point 功能来寻找几个合适的点位。打开 Publish Point 功能, 并移动鼠标到对应目标点位,此时rviz左下角会显示该点位坐标的三个值,前两个值即为x和y值。

(您可以先根据前面我们提供的教程来学习如何用雷达来建图。)

  • 当您设定好点位后,即可修改代码中ABCD点相应参数(这里的ABCD点可以具象化为对应的位置,比如厨房,客厅,卫生间等)来设定点位。

  • 此处我们演示了A点的例子:

//set_goal.py
if msg.data == 'A':
            self.pose_x = rospy.get_param('~goal_pose_x',11.3)//只需要修改这两个点位X坐标
            self.pose_y = rospy.get_param('~goal_pose_y',50.1)//Y坐标
            self.pose_z = rospy.get_param('~goal_pose_z',0.0)

            self.quat_x = rospy.get_param('~goal_quat_x',0.0)
            self.quat_y = rospy.get_param('~goal_quat_y',0.0)
            self.quat_z = rospy.get_param('~goal_quat_z',0.0)
            self.quat_w = rospy.get_param('~goal_quat_w',1.0)
  • 这时候再通过我们的语音交互下达相应的指令,当小道小道唤醒后,使用去A点指令发出,就可以实现机器人的语音导航功能。

下面是一个科大讯飞的错误码信息查询,如果在调用科大讯飞的时候报错了相关的错误码,可以通过这个链接查询。 科大讯飞错误码信息查询

results matching ""

    No results matching ""