题目要求:通过对科大讯飞SDK的使用,实现对机器人的语音控制。
提前说明:本贴只是能识别两个英文(forward,stop)。其余语音同理。
个人思路:因为我们根据视频中所讲,已经知道iat_publish.cpp的功能是:语音听写(iFly Auto Transform)技术能够实时地将语音转换成对应的文字。发布一个话题"voiceWords"
ros::Publisher voiceWordsPub = n.advertise<std_msgs::String>("voiceWords", 1000);
所以只需要创建一个node订阅voiceWords这个话题,并在回调函数中实现对速度的赋值,并在cmd_vel话题中将消息
geometry_msgs::Twist vel_msg
发布,就能实现对小车的控制。
解决方案:
1> 创建voice_controll.cpp,其内容如下,
/*
*此节点订阅语音消息,发布速度指令
*/
#include<ros/ros.h>
#include<geometry_msgs/Twist.h>
#include<std_msgs/String.h>
#include<string>
//string forward = "forward";
//String backward = "向后";
//String leftward = "向左";
//String rightward = "向右";
geometry_msgs::Twist vel_msg; //发布的速度消息
void voiceCallback(const std_msgs::StringConstPtr& msg)//回调函数,接收到voice后启动该函数
{
//ROS_INFO("msg get!");
// 将接收到的消息打印出来
ROS_INFO("I heard: [%s]", msg->data.c_str());
if (msg->data == "forward\u3002")
{
vel_msg.linear.x = 1.0;
ROS_INFO("forward vel_msg has been modifided!");
}
if (msg->data == "stop\uFF01")
{
vel_msg.linear.x = 0.0;
ROS_INFO("stop!!");
}
/*
if (msg->data = backword)
{
}
if (msg->data = leftward)
{
}
if (msg->data = rightword)
{
}
*/
}
int main(int argc, char *argv[])
{
ros::init(argc, argv, "voice_controll");
ros::NodeHandle node;
ros::Subscriber sub = node.subscribe("voiceWords",1000,voiceCallback); //订阅语音识别之后的话题
ros::Publisher pub = node.advertise<geometry_msgs::Twist>("/cmd_vel",10);//定义一个速度发布者
ros::Rate rate(10); //频率
while (ros::ok())
{
pub.publish(vel_msg);
ros::spinOnce();
rate.sleep();
}
return 0;
}
2> 创建launch文件voice_controll.launch如下,
<launch>
<arg name="model" default="$(find xacro)/xacro --inorder '$(find wheel_chair_description)/urdf/wheel_chair.xacro'" />
<arg name="gui" default="true" />
<param name="robot_description" command="$(arg model)" />
<!-- 设置GUI参数,显示关节控制插件 -->
<param name="use_gui" value="$(arg gui)"/>
<node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
<rosparam file="$(find wheel_chair_description)/config/fake_wheel_chair_arbotix.yaml" command="load" />
<param name="sim" value="true"/>
</node>
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- 运行rviz可视化界面 -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find wheel_chair_description)/config/wheel_chair_arbotix.rviz" required="true" />
<!--运行自己写的语音控制节点voice_controll-->
<node name="voice_controll" pkg="robot_voice" type="voice_controll" output="screen"/>
<!--运行一个语音识别节点iat_publish,基于科大讯飞语音识别的文件-->
<node name="iat_publish" pkg="robot_voice" type="iat_publish" output="screen"/>
</launch>
该文件借鉴之前的wheel_chair文件,具体的wheel_chair_description文件见https://github.com/suyunzzz/ROS_homework。
3> 启动上述的launch文件,但是iat_publish节点需要订阅一个话题以激活,所以新开一个终端输入激活消息
rostopic pub /voiceWakeup std_msgs/String "data: 'any thing'"
然后根据提示发出指令即可。
运行结果如下图:
s@s:~$ roslaunch robot_voice voice_controll.launch
... logging to /home/s/.ros/log/2086a790-a63f-11e9-9860-485f9946ea55/roslaunch-s-13920.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://s:46537/
SUMMARY
========
PARAMETERS
* /arbotix/controllers/base_controller/Kd: 12
* /arbotix/controllers/base_controller/Ki: 0
* /arbotix/controllers/base_controller/Ko: 50
* /arbotix/controllers/base_controller/Kp: 12
* /arbotix/controllers/base_controller/accel_limit: 1.0
* /arbotix/controllers/base_controller/base_frame_id: base_footprint
* /arbotix/controllers/base_controller/base_width: 0.26
* /arbotix/controllers/base_controller/ticks_meter: 4100
* /arbotix/controllers/base_controller/type: diff_controller
* /arbotix/sim: True
* /robot_description: <?xml version="1....
* /rosdistro: kinetic
* /rosversion: 1.12.14
* /use_gui: True
NODES
/
arbotix (arbotix_python/arbotix_driver)
iat_publish (robot_voice/iat_publish)
joint_state_publisher (joint_state_publisher/joint_state_publisher)
robot_state_publisher (robot_state_publisher/robot_state_publisher)
rviz (rviz/rviz)
voice_controll (robot_voice/voice_controll)
auto-starting new master
process[master]: started with pid [13933]
ROS_MASTER_URI=http://localhost:11311
setting /run_id to 2086a790-a63f-11e9-9860-485f9946ea55
process[rosout-1]: started with pid [13946]
started core service [/rosout]
process[arbotix-2]: started with pid [13957]
process[joint_state_publisher-3]: started with pid [13964]
process[robot_state_publisher-4]: started with pid [13965]
process[rviz-5]: started with pid [13966]
process[voice_controll-6]: started with pid [13968]
process[iat_publish-7]: started with pid [13982]
[ INFO] [1563112567.900509661]: Sleeping...
[INFO] [1563112568.364309]: ArbotiX being simulated.
[INFO] [1563112568.376347]: Started DiffController (base_controller). Geometry: 0.26m wide, 4100.0 ticks/m.
waking up
[ INFO] [1563112578.698446265]: Wakeup...
Demo recognizing the speech from microphone
Speak in 10 seconds
Start Listening...
Result: [ forward。 ]
Speaking done
Not started or already stopped.
10 sec passed
[ INFO] [1563112588.791570908]: I heard: [forward???]
[ INFO] [1563112588.791655105]: forward vel_msg has been modifided!
^C[iat_publish-7] killing on exit
[voice_controll-6] killing on exit
[rviz-5] killing on exit
[robot_state_publisher-4] killing on exit
[joint_state_publisher-3] killing on exit
[arbotix-2] killing on exit
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done
s@s:~$ rostopic pub /voiceWakeup std_msgs/String "data: '2'"
publishing and latching message. Press ctrl-C to terminate