forked from mikeferguson/pocketsphinx
-
Notifications
You must be signed in to change notification settings - Fork 4
/
Copy pathvoice_cmd_vel.py
executable file
·80 lines (66 loc) · 2.38 KB
/
voice_cmd_vel.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
#!/usr/bin/env python
"""
voice_cmd_vel.py is a simple demo of speech recognition.
You can control a mobile base using commands found
in the corpus file.
"""
import roslib; roslib.load_manifest('pocketsphinx')
import rospy
import math
from geometry_msgs.msg import Twist
from std_msgs.msg import String
class voice_cmd_vel:
def __init__(self):
rospy.on_shutdown(self.cleanup)
self.speed = 0.2
self.msg = Twist()
# publish to cmd_vel, subscribe to speech output
self.pub_ = rospy.Publisher('cmd_vel', Twist)
rospy.Subscriber('recognizer/output', String, self.speechCb)
r = rospy.Rate(10.0)
while not rospy.is_shutdown():
self.pub_.publish(self.msg)
r.sleep()
def speechCb(self, msg):
rospy.loginfo(msg.data)
if msg.data.find("full speed") > -1:
if self.speed == 0.2:
self.msg.linear.x = self.msg.linear.x*2
self.msg.angular.z = self.msg.angular.z*2
self.speed = 0.4
if msg.data.find("half speed") > -1:
if self.speed == 0.4:
self.msg.linear.x = self.msg.linear.x/2
self.msg.angular.z = self.msg.angular.z/2
self.speed = 0.2
if msg.data.find("forward") > -1:
self.msg.linear.x = self.speed
self.msg.angular.z = 0
elif msg.data.find("left") > -1:
if self.msg.linear.x != 0:
if self.msg.angular.z < self.speed:
self.msg.angular.z += 0.05
else:
self.msg.angular.z = self.speed*2
elif msg.data.find("right") > -1:
if self.msg.linear.x != 0:
if self.msg.angular.z > -self.speed:
self.msg.angular.z -= 0.05
else:
self.msg.angular.z = -self.speed*2
elif msg.data.find("back") > -1:
self.msg.linear.x = -self.speed
self.msg.angular.z = 0
elif msg.data.find("stop") > -1 or msg.data.find("halt") > -1:
self.msg = Twist()
self.pub_.publish(self.msg)
def cleanup(self):
# stop the robot!
twist = Twist()
self.pub_.publish(twist)
if __name__=="__main__":
rospy.init_node('voice_cmd_vel')
try:
voice_cmd_vel()
except:
pass