mirror of
https://github.com/6-robot/wpb_home.git
synced 2025-09-15 12:58:59 +08:00
fix voice_cmd
This commit is contained in:
parent
8ab03de514
commit
01181196f6
@ -52,23 +52,29 @@ void KeywordCB(const std_msgs::String::ConstPtr & msg)
|
||||
vel_cmd.angular.y = 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;
|
||||
}
|
||||
if(msg->data.find("backward")>0)
|
||||
nFindIndex = msg->data.find("backward");
|
||||
if(nFindIndex >= 0)
|
||||
{
|
||||
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;
|
||||
}
|
||||
if(msg->data.find("right")>0)
|
||||
nFindIndex = msg->data.find("right");
|
||||
if(nFindIndex >= 0)
|
||||
{
|
||||
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.y = 0;
|
||||
|
||||
Loading…
Reference in New Issue
Block a user