3 from geometry_msgs.msg
import TwistStamped
4 from sensor_msgs.msg
import JointState
5 import termios, fcntl, sys, os
9 from std_srvs.srv
import Empty
13 twist_topic=
"/uwsim/g500_B/twist_command" 18 fd = sys.stdin.fileno()
19 oldterm = termios.tcgetattr(fd)
20 newattr = termios.tcgetattr(fd)
21 newattr[3] = newattr[3] & ~termios.ICANON & ~termios.ECHO
22 termios.tcsetattr(fd, termios.TCSANOW, newattr)
23 oldflags = fcntl.fcntl(fd, fcntl.F_GETFL)
24 fcntl.fcntl(fd, fcntl.F_SETFL, oldflags | os.O_NONBLOCK)
27 pubTwist = rospy.Publisher(twist_topic, TwistStamped, queue_size=1)
28 rospy.init_node(
'keyboardCommandVeh_B')
29 msgTwist = TwistStamped()
34 while not rospy.is_shutdown():
37 msgTwist = TwistStamped()
46 msgTwist.twist.angular.y=-baseVelocity
48 msgTwist.twist.angular.y=baseVelocity
50 msgTwist.twist.angular.z=baseVelocity
52 msgTwist.twist.angular.z=-baseVelocity
54 msgTwist.twist.linear.x = baseVelocity
56 msgTwist.twist.linear.x = -baseVelocity
58 msgTwist.twist.linear.y = baseVelocity
60 msgTwist.twist.linear.y = -baseVelocity
62 msgTwist.twist.linear.z = baseVelocity
64 msgTwist.twist.linear.z = -baseVelocity
66 msgTwist.twist.angular.x = -baseVelocity
68 msgTwist.twist.angular.x = baseVelocity
72 print "baseVelocity: " , baseVelocity
74 if baseVelocity > 0.2:
76 elif baseVelocity > 0:
80 print "baseVelocity: " , baseVelocity
82 print 'wrong key pressed, and reset all vehicle velocities' 83 msgTwist = TwistStamped()
84 modality =
not modality
91 print 'velocity vehicle published:' 92 print (msgTwist.twist.linear.x, msgTwist.twist.linear.y, msgTwist.twist.linear.z)
93 print (msgTwist.twist.angular.x, msgTwist.twist.angular.y, msgTwist.twist.angular.z )
94 pubTwist.publish(msgTwist)
99 termios.tcsetattr(fd, termios.TCSAFLUSH, oldterm)
100 fcntl.fcntl(fd, fcntl.F_SETFL, oldflags)