上篇介绍了ros里如何编写话题订阅者和发布者,本篇来做一个简单的应用,语音控制机器人行动。
视频展示地址:http://blog.jiutucao.com:9000/upload/2018/07/speech_move.mp4
在写代码之前需要电脑里配置pocketsphinx,这是一个开源的离线语音识别包,配置的方法自行百度,需要自己训练字库,建议字库不要太复杂,毕竟中国人说英文不是那么标准,太复杂的字库识别率太低。
程序思路很简单:
Pocketsphinx识别出语音后,会将识别出的语音发布到/Rog_result话题上,我们只需要订阅/Rog_result的消息,对数据做个判断,然后在回调函数里对速度数据进行处理,最后发布到控制速度的/cmd_vel话题上。由于训练的字库并不复杂,Pocketsphinx只能识别出字库里的内容,所以判断也并不复杂。
代码:speech_teleop.cpp
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <geometry_msgs/Twist.h>
#include <string>
#include <iostream>
using namespace std;
class voicespeech{
public:
float line;
float angle;
ros::Subscriber sub;
voicespeech(ros::NodeHandle n);
void speechvoiceCallback(const std_msgs::String::ConstPtr& msg);
void move();
void stop();
void fast();
void slow();
void left();
void right();
};
voicespeech::voicespeech(ros::NodeHandle n){
line = 0.2;
angle = 0;
sub = n.subscribe<std_msgs::String>("/Rog_result",10,&voicespeech::speechvoiceCallback,this);
}
void voicespeech::speechvoiceCallback(const std_msgs::String::ConstPtr& msg){
ROS_INFO(msg->data.c_str());
std::string command = msg->data;
if(command.compare("启动") == 0){
move();
}else if(command.compare("停止") == 0){
stop();
}else if(command.compare("加速") == 0){
fast();
}else if(command.compare("减速") == 0){
slow();
}else if(command.compare("左转") == 0){
left();
}else if(command.compare("右转") == 0){
right();
}else{
ROS_INFO("no command");
}
}
void voicespeech::move(){
line = 0.2;
angle = 0;
}
void voicespeech::stop(){
line = 0;
angle = 0;
}
void voicespeech::fast(){
line = line + 0.1;
angle = 0;
}
void voicespeech::slow(){
line = line - 0.1;
angle = 0;
}
void voicespeech::left(){
angle = angle + 0.1;
}
void voicespeech::right(){
//line = 0.2;
angle = angle - 0.1;
}
int main(int argc, char** argv){
ros::init(argc , argv ,"voice_speech");
ros::NodeHandle n;
voicespeech vs(n);
ros::Publisher pub = n.advertise<geometry_msgs::Twist>("cmd_vel",1);
ros::Rate loop_rate(10);
while(ros::ok()){
geometry_msgs::Twist twist;
twist.linear.x = vs.line;
twist.angular.z = vs.angle;
pub.publish(twist);
ros::spinOnce();
loop_rate.sleep();
}
ros::spin();
return 0;
}
Cmakelist.txt
添加如下代码:
set(NODE_MOVE_TEST
src/move_test/speech_teleop.cpp
)
add_executable(speech_teleop ${NODE_MOVE_TEST} )
target_link_libraries(speech_teleop openrobotComm ${catkin_LIBRARIES})
launch文件
speech_teleop.launch
<launch>
<node name="recognizer" pkg="pocketsphinx" type="recognizer.py" output="screen">
<param name="lm" value="/home/tt/ppp/src/openrobot/speech_conf/command.lm"/>
<param name="dict" value="/home/tt/ppp/src/openrobot/speech_conf/command.dic"/>
</node>
<node pkg="openrobot" type="speech_teleop" name="speech_teleop"></node>
</launch>
在launch文件中要指明语音库的路径
运行测试;
连接好设备后,运行launch文件即可

本文介绍了一种使用ROS实现的语音控制机器人行动的方法。通过pocketsphinx离线语音识别包,将识别出的语音发布到特定话题,再通过订阅和处理这些消息来控制机器人的速度和方向。
2105

被折叠的 条评论
为什么被折叠?



