fix voice_cmd

This commit is contained in:
ZhangWanjie 2017-03-28 20:10:53 +08:00
parent 8ab03de514
commit 01181196f6

View File

@ -52,23 +52,29 @@ void KeywordCB(const std_msgs::String::ConstPtr & msg)
vel_cmd.angular.y = 0; vel_cmd.angular.y = 0;
vel_cmd.angular.z = 0; vel_cmd.angular.z = 0;
if(msg->data.find("forward")>0) int nFindIndex = 0;
nFindIndex = msg->data.find("forward");
if(nFindIndex >= 0)
{ {
vel_cmd.linear.x = 0.1; vel_cmd.linear.x = 0.1;
} }
if(msg->data.find("backward")>0) nFindIndex = msg->data.find("backward");
if(nFindIndex >= 0)
{ {
vel_cmd.linear.x = -0.1; vel_cmd.linear.x = -0.1;
} }
if(msg->data.find("left")>0) nFindIndex = msg->data.find("left");
if(nFindIndex >= 0)
{ {
vel_cmd.linear.y = 0.1; vel_cmd.linear.y = 0.1;
} }
if(msg->data.find("right")>0) nFindIndex = msg->data.find("right");
if(nFindIndex >= 0)
{ {
vel_cmd.linear.y = -0.1; vel_cmd.linear.y = -0.1;
} }
if(msg->data.find("stop")>0) nFindIndex = msg->data.find("stop");
if(nFindIndex >= 0)
{ {
vel_cmd.linear.x = 0; vel_cmd.linear.x = 0;
vel_cmd.linear.y = 0; vel_cmd.linear.y = 0;