Contents
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 中文语音交互模块使用手册
You can skip these steps if you purchase ROSECHO with a ROS2GO system
To be released
Steps to install to catkin_ws. Tested for ROS kinetic and melodic.
Make sure the power supply and usb connection are correct. Start ROSECHO node Launch the ROSECHO. 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 To enable wifi config, call the wifi_cfg service. You can use Tab to auto-complete the command and then fill in the ssid and password. check the automated sound recognition result check the answer send tts to rosecho/tts/goal You can use Tab to auto-complete the command and then fill in the goal: text: '你好机器人'
Voice command test in turtlebot stage
The package is under BSD 3-Clause License Installation
Install from debian package
Install from source
cd ~/catkin_ws/src/
git clone https://github.com/tianbot/rosecho.git
cd ~/catkin_ws && catkin_make
Usage Instructions
roslaunch rosecho rosecho.launch
roslaunch rosecho rosecho.launch serial_port:=/dev/ttyUSB1
rosservice call /rosecho/wifi_cfg "ssid: 'tianbot' password: 'www.tianbot.com'"
rosrun rosecho asr_echo.py
rosrun rosecho answer_echo.py
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: '你好机器人'"
Simple Demo
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)
/rosecho/tts/cancel (actionlib_msgs/GoalID) Published Topics
/rosecho/answer (std_msgs/String)
/rosecho/asr (std_msgs/String)
/rosecho/wakeup_pos (std_msgs/Int16)
/rosecho/tts/feedback (rosecho/ttsActionFeedback)
/rosecho/tts/result (rosecho/ttsActionResult)
/rosecho/tts/status (actionlib_msgs/GoalStatus) Services
/rosecho/disable (std_srvs/Empty)
/rosecho/enable (std_srvs/Empty)
/rosecho/sleep (std_srvs/Empty)
/rosecho/wakeup (std_srvs/Empty)
/rosecho/wifi_cfg (rosecho/WifiCfg) License