AUV-Coop-Assembly
Master Thesis for Robotics Engineering. Cooperative peg-in-hole assembly with two underwater vehicles guided by vision
keyboardCommand_A.py
1 #!/usr/bin/env python
2 
3 from geometry_msgs.msg import TwistStamped
4 from sensor_msgs.msg import JointState
5 import termios, fcntl, sys, os
6 import rospy
7 
8 #import service library
9 from std_srvs.srv import Empty
10 
11 #topic to command
12 # Twist better than odometry TODO ask why
13 twist_topic="/uwsim/g500_A/twist_command"
14 joint_topic="/uwsim/g500_A/joint_command"
15 #base velocity for the teleoperation
16 baseVelocity=0.8
17 baseJoint=0.1
18 
19 #Console input variables to teleop it from the console
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)
27 
28 ##create the publishers
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()
34 modality = True # true: at each while velocitty is resetted
35 
36 #The try is necessary for the console input!
37 try:
38  while not rospy.is_shutdown():
39 
40  msgJoint = JointState()
41 
42  if (modality):
43  msgTwist = TwistStamped()
44 
45  try:
46  c = sys.stdin.read(1)
47  ##Depending on the character set the proper speeds
48  if c=='\x1b': ##This means we are pressing an arrow!
49  c2= sys.stdin.read(1)
50  c2= sys.stdin.read(1)
51  if c2=='A':
52  msgTwist.twist.angular.y=-baseVelocity
53  elif c2=='B':
54  msgTwist.twist.angular.y=baseVelocity
55  elif c2 == 'C':
56  msgTwist.twist.angular.z=baseVelocity
57  elif c2 == 'D':
58  msgTwist.twist.angular.z=-baseVelocity
59  elif c == 'w':
60  msgTwist.twist.linear.x = baseVelocity
61  elif c == 's':
62  msgTwist.twist.linear.x = -baseVelocity
63  elif c == 'd':
64  msgTwist.twist.linear.y = baseVelocity
65  elif c == 'a':
66  msgTwist.twist.linear.y = -baseVelocity
67  elif c == 'v':
68  msgTwist.twist.linear.z = baseVelocity
69  elif c == 'f':
70  msgTwist.twist.linear.z = -baseVelocity
71  elif c == 'q':
72  msgTwist.twist.angular.x = -baseVelocity
73  elif c == 'e':
74  msgTwist.twist.angular.x = baseVelocity
75  #JointsCommands
76  elif c == 't':
77  msgJoint.name.append("Slew")
78  msgJoint.velocity.append(baseJoint)
79  elif c == 'z':
80  msgJoint.name.append("Shoulder")
81  msgJoint.velocity.append(baseJoint)
82  elif c == 'u':
83  msgJoint.name.append("Elbow")
84  msgJoint.velocity.append(baseJoint)
85  elif c == 'i':
86  msgJoint.name.append("JawRotate")
87  msgJoint.velocity.append(baseJoint)
88  elif c == 'o':
89  msgJoint.name.append("JawOpening")
90  msgJoint.velocity.append(baseJoint)
91  elif c == 'g':
92  msgJoint.name.append("Slew")
93  msgJoint.velocity.append(-baseJoint)
94  elif c == 'h':
95  msgJoint.name.append("Shoulder")
96  msgJoint.velocity.append(-baseJoint)
97  elif c == 'j':
98  msgJoint.name.append("Elbow")
99  msgJoint.velocity.append(-baseJoint)
100  elif c == 'k':
101  msgJoint.name.append("JawRotate")
102  msgJoint.velocity.append(-baseJoint)
103  elif c == 'l':
104  msgJoint.name.append("JawOpening")
105  msgJoint.velocity.append(-baseJoint)
106  #Increase Velocity send command
107  elif c == 'y':
108  baseVelocity+=0.1;
109  print "baseVelocity: " , baseVelocity
110  elif c == 'x':
111  if baseVelocity > 0.2:
112  baseVelocity-=0.1
113  elif baseVelocity > 0:
114  baseVelocity -= 0.01
115  else:
116  baseVelocity = 0
117  print "baseVelocity: " , baseVelocity
118  elif c == 'n':
119  baseJoint+=0.1;
120  print "jointVelocity: " , baseJoint
121  elif c == 'm':
122  if baseJoint > 0.2:
123  baseJoint -= 0.1
124  elif baseJoint > 0:
125  baseJoint -= 0.01
126  else:
127  baseJoint = 0
128  print "jointVelocity: ", baseJoint
129  else:
130  print 'wrong key pressed, and reset all vehicle and joint velocities'
131  msgTwist = TwistStamped()
132  msgJoint = JointState()
133  modality = not modality
134 
135  while c!='':
136  c = sys.stdin.read(1)
137  except IOError: pass
138 
139  ##publish the message
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)
145  rospy.sleep(0.1)
146 
147 ##Other input stuff
148 finally:
149  termios.tcsetattr(fd, termios.TCSAFLUSH, oldterm)
150  fcntl.fcntl(fd, fcntl.F_SETFL, oldflags)