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_A/twist_command" 14 joint_topic=
"/uwsim/g500_A/joint_command" 20 fd = sys.stdin.fileno()
21 oldterm = termios.tcgetattr(fd)
22 newattr = termios.tcgetattr(fd)
23 newattr[3] = newattr[3] & ~termios.ICANON & ~termios.ECHO
24 termios.tcsetattr(fd, termios.TCSANOW, newattr)
25 oldflags = fcntl.fcntl(fd, fcntl.F_GETFL)
26 fcntl.fcntl(fd, fcntl.F_SETFL, oldflags | os.O_NONBLOCK)
29 pubTwist = rospy.Publisher(twist_topic, TwistStamped,queue_size=1)
30 pubJoint = rospy.Publisher(joint_topic, JointState,queue_size=1)
31 rospy.init_node(
'keyboardCommand_A')
32 msgTwist = TwistStamped()
33 msgJoint = JointState()
38 while not rospy.is_shutdown():
40 msgJoint = JointState()
43 msgTwist = TwistStamped()
52 msgTwist.twist.angular.y=-baseVelocity
54 msgTwist.twist.angular.y=baseVelocity
56 msgTwist.twist.angular.z=baseVelocity
58 msgTwist.twist.angular.z=-baseVelocity
60 msgTwist.twist.linear.x = baseVelocity
62 msgTwist.twist.linear.x = -baseVelocity
64 msgTwist.twist.linear.y = baseVelocity
66 msgTwist.twist.linear.y = -baseVelocity
68 msgTwist.twist.linear.z = baseVelocity
70 msgTwist.twist.linear.z = -baseVelocity
72 msgTwist.twist.angular.x = -baseVelocity
74 msgTwist.twist.angular.x = baseVelocity
77 msgJoint.name.append(
"Slew")
78 msgJoint.velocity.append(baseJoint)
80 msgJoint.name.append(
"Shoulder")
81 msgJoint.velocity.append(baseJoint)
83 msgJoint.name.append("Elbow")
84 msgJoint.velocity.append(baseJoint)
86 msgJoint.name.append(
"JawRotate")
87 msgJoint.velocity.append(baseJoint)
89 msgJoint.name.append(
"JawOpening")
90 msgJoint.velocity.append(baseJoint)
92 msgJoint.name.append(
"Slew")
93 msgJoint.velocity.append(-baseJoint)
95 msgJoint.name.append(
"Shoulder")
96 msgJoint.velocity.append(-baseJoint)
98 msgJoint.name.append(
"Elbow")
99 msgJoint.velocity.append(-baseJoint)
101 msgJoint.name.append(
"JawRotate")
102 msgJoint.velocity.append(-baseJoint)
104 msgJoint.name.append(
"JawOpening")
105 msgJoint.velocity.append(-baseJoint)
109 print "baseVelocity: " , baseVelocity
111 if baseVelocity > 0.2:
113 elif baseVelocity > 0:
117 print "baseVelocity: " , baseVelocity
120 print "jointVelocity: " , baseJoint
128 print "jointVelocity: ", baseJoint
130 print 'wrong key pressed, and reset all vehicle and joint velocities' 131 msgTwist = TwistStamped()
132 msgJoint = JointState()
133 modality =
not modality
136 c = sys.stdin.read(1)
140 print 'velocity vehicle published:' 141 print (msgTwist.twist.linear.x, msgTwist.twist.linear.y, msgTwist.twist.linear.z)
142 print (msgTwist.twist.angular.x, msgTwist.twist.angular.y, msgTwist.twist.angular.z )
143 pubTwist.publish(msgTwist)
144 pubJoint.publish(msgJoint)
149 termios.tcsetattr(fd, termios.TCSAFLUSH, oldterm)
150 fcntl.fcntl(fd, fcntl.F_SETFL, oldflags)