voice_cmd_vel.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """
00004 voice_cmd_vel.py is a simple demo of speech recognition.
00005   You can control a mobile base using commands found
00006   in the corpus file.
00007 """
00008 
00009 import roslib; roslib.load_manifest('pocketsphinx')
00010 import rospy
00011 import math
00012 
00013 from geometry_msgs.msg import Twist
00014 from std_msgs.msg import String
00015 
00016 class voice_cmd_vel:
00017 
00018     def __init__(self):
00019         rospy.on_shutdown(self.cleanup)
00020         self.speed = 0.2
00021         self.msg = Twist()
00022 
00023         # publish to cmd_vel, subscribe to speech output
00024         self.pub_ = rospy.Publisher('cmd_vel', Twist)
00025         rospy.Subscriber('recognizer/output', String, self.speechCb)
00026 
00027         r = rospy.Rate(10.0)
00028         while not rospy.is_shutdown():
00029             self.pub_.publish(self.msg)
00030             r.sleep()
00031         
00032     def speechCb(self, msg):
00033         rospy.loginfo(msg.data)
00034 
00035         if msg.data.find("full speed") > -1:
00036             if self.speed == 0.2:
00037                 self.msg.linear.x = self.msg.linear.x*2
00038                 self.msg.angular.z = self.msg.angular.z*2
00039                 self.speed = 0.4
00040         if msg.data.find("half speed") > -1:
00041             if self.speed == 0.4:
00042                 self.msg.linear.x = self.msg.linear.x/2
00043                 self.msg.angular.z = self.msg.angular.z/2
00044                 self.speed = 0.2
00045 
00046         if msg.data.find("forward") > -1:    
00047             self.msg.linear.x = self.speed
00048             self.msg.angular.z = 0
00049         elif msg.data.find("left") > -1:
00050             if self.msg.linear.x != 0:
00051                 if self.msg.angular.z < self.speed:
00052                     self.msg.angular.z += 0.05
00053             else:        
00054                 self.msg.angular.z = self.speed*2
00055         elif msg.data.find("right") > -1:    
00056             if self.msg.linear.x != 0:
00057                 if self.msg.angular.z > -self.speed:
00058                     self.msg.angular.z -= 0.05
00059             else:        
00060                 self.msg.angular.z = -self.speed*2
00061         elif msg.data.find("back") > -1:
00062             self.msg.linear.x = -self.speed
00063             self.msg.angular.z = 0
00064         elif msg.data.find("stop") > -1 or msg.data.find("halt") > -1:          
00065             self.msg = Twist()
00066         
00067         self.pub_.publish(self.msg)
00068 
00069     def cleanup(self):
00070         # stop the robot!
00071         twist = Twist()
00072         self.pub_.publish(twist)
00073 
00074 if __name__=="__main__":
00075     rospy.init_node('voice_cmd_vel')
00076     try:
00077         voice_cmd_vel()
00078     except:
00079         pass
00080 


pocketsphinx
Author(s): Michael Ferguson
autogenerated on Thu Aug 27 2015 14:21:54