Introduction

Tianbot Rosecho (Tianecho),a Chinese speech recognition sensor for robots to hear the world.ROSECHO is based on iFlyTek IFLYOS system, the AIUI development kit. Rosecho github repo 中文语音交互模块使用手册

Installation

You can skip these steps if you purchase ROSECHO with a ROS2GO system

Install from debian package

To be released

Install from source

Steps to install to catkin_ws. Tested for ROS kinetic and melodic.

cd ~/catkin_ws/src/
git clone https://github.com/tianbot/rosecho.git
cd ~/catkin_ws && catkin_make

Usage Instructions

Make sure the power supply and usb connection are correct.

Start ROSECHO node Launch the ROSECHO.

roslaunch rosecho rosecho.launch

The default serial port is /dev/ttyUSB0, if serial open failed, pls check the port used by ROSECHO If it is /dev/ttyUSB1, you can change the launch file or launch use the command as follows

roslaunch rosecho rosecho.launch serial_port:=/dev/ttyUSB1

To enable wifi config, call the wifi_cfg service.

rosservice call /rosecho/wifi_cfg "ssid: 'tianbot' password: 'www.tianbot.com'"

You can use Tab to auto-complete the command and then fill in the ssid and password.

check the automated sound recognition result

rosrun rosecho asr_echo.py

check the answer

rosrun rosecho answer_echo.py

send tts to rosecho/tts/goal

rostopic pub /rosecho/tts/goal rosecho/ttsActionGoal "header:
  seq: 0
  stamp:
    secs: 0
    nsecs: 0
  frame_id: ''
goal_id:
  stamp:
    secs: 0
    nsecs: 0
  id: ''
goal:
  text: '你好机器人'"

You can use Tab to auto-complete the command and then fill in the goal: text: '你好机器人'

Simple Demo

Voice command test in turtlebot stage

roslaunch rosecho rosecho.launch
roslaunch turtlebot_stage turtlebot_in_stage.launch
rosrun rosecho demo.py

Nodes

rosecho

rosecho is the main function.

Subscribed Topics

/rosecho/tts/goal (rosecho/ttsActinoGoal)
  • The ROSECHO tts status.
/rosecho/tts/cancel (actionlib_msgs/GoalID)
  • Cancel goal, interupt the current TTS action.

Published Topics

/rosecho/answer (std_msgs/String)
  • The answer returned by iflyos.
/rosecho/asr (std_msgs/String)
  • Speech recognized result.
/rosecho/wakeup_pos (std_msgs/Int16)
  • Position of the speaker when wakeup.
/rosecho/tts/feedback (rosecho/ttsActionFeedback)
  • Currently no output.
/rosecho/tts/result (rosecho/ttsActionResult)
  • Return success when finish TTS.
/rosecho/tts/status (actionlib_msgs/GoalStatus)
  • The ROSECHO tts status.

Services

/rosecho/disable (std_srvs/Empty)
  • Disable the service.
/rosecho/enable (std_srvs/Empty)
  • Enable the service.
/rosecho/sleep (std_srvs/Empty)
  • Enter sleep mode if awaken.
/rosecho/wakeup (std_srvs/Empty)
  • Manually wakeup.
/rosecho/wifi_cfg (rosecho/WifiCfg)
  • Setup WIFI connection.

License

The package is under BSD 3-Clause License

Wiki: rosecho (last edited 2020-03-31 04:51:16 by tianbot)