-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathroomba_move_create_2.py
250 lines (197 loc) · 4.99 KB
/
roomba_move_create_2.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
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
#!/usr/bin/env python
import rospy
from geometry_msgs.msg import Twist
from math import pow,atan2,sqrt
from nav_msgs.msg import Odometry
import tf
from math import radians, degrees, sqrt
from time import sleep
from ca_msgs.msg import Bumper
rospy.init_node("roomba_2_pid_controller")
velocity_publisher = rospy.Publisher('roomba3/cmd_vel', Twist, queue_size=10)
rate = rospy.Rate(10.0)
listener = tf.TransformListener()
def check_camera():
got_one = False
while not got_one:
try:
(t,rot) = listener.lookupTransform('/map', '/roomba3', rospy.Time(0))
got_one = True
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
continue
euler = tf.transformations.euler_from_quaternion(rot)
yaw = euler[2]
quat = tf.transformations.quaternion_from_euler(0.0,0.0,yaw)
trans = (t[0],t[1],0.0)
return (trans,quat)
def publish_cmd_vel(lin_vel, angle_vel):
vel_msg = Twist()
vel_msg.linear.x = lin_vel
vel_msg.angular.z = angle_vel
velocity_publisher.publish(vel_msg)
def bumperData():
bumper_msg = rospy.wait_for_message("roomba3/bumper", Bumper)
check = False
if (bumper_msg.is_left_pressed or bumper_msg.is_right_pressed):
check = True
return check
def moveTo(distance):
publish_cmd_vel(0.0,0.0)
sleep(1)
tries = 0
kp = 0.45
ki = 0.005
kd = 0
integral = 0
last_error = 0
derivative = 0
i = 0
target_achieved = False
target = distance
(trans,rot) = check_camera()
x_init = trans[0]
y_init = trans[1]
while not target_achieved:
check = bumperData()
if check == True:
break
(trans,quat) = check_camera()
cur_x = trans[0]
cur_y = trans[1]
cur_d = sqrt((cur_x - x_init)**2 + (cur_y - y_init)**2)
error = abs(target) - cur_d
print "Error: "+ str(error)
integral += error
derivative = error - last_error
if (error>0 and last_error <0) or (error<0 and last_error>0):
integral = 0
publish_cmd_vel(0.0,0.0)
print "***Flipped Integral***"
sleep(1)
if derivative >= 0.05:
integral = 0
print "Integral: " + str(integral)
print "Derivative: " + str(derivative)
lin_vel = kp*error + ki*integral + kd*derivative
print "Lin_vel: " + str(lin_vel)
if abs(error) < 0.01:
lin_vel = 0
i += 1
publish_cmd_vel(lin_vel,0)
last_error = error
print "---"
if i >= 5:
target_achieved = True
rate.sleep()
tries += 1
if tries >= 1000:
target_achieved = True
print "Giving up"
publish_cmd_vel(0,0)
check = bumperData()
if check == True:
for i in range(0,5):
publish_cmd_vel(0,0)
rate.sleep()
sleep(2)
for i in range(0,10):
publish_cmd_vel(-0.2, 0)
rate.sleep()
publish_cmd_vel(0,0)
def rotateTo(angle):
publish_cmd_vel(0.0,0.0)
sleep(1)
tries = 0
kp = 0.5
ki = 0.02
kd = 0.0
integral = 0
last_error = 0
derivative = 0
i = 0
target_achieved = False
target = angle
while not target_achieved:
check = bumperData()
if check == True:
break
(trans,quat) = check_camera()
euler = tf.transformations.euler_from_quaternion(quat)
yaw = euler[2]
error = target - yaw
if error > radians(180):
error = error - radians(360)
if error < radians(-180):
error = error + radians(360)
print "Error: "+ str(error)
integral += error
if (error > 0 and last_error < 0) or (error<0 and last_error>0):
intergal = 0.0
print "Flipped INTEGRAL***"
derivative = error - last_error
if abs(derivative)*1000 > 10:
integral = 0.0
ang_vel = kp*error + ki*integral + kd*derivative
print "Integral: " + str(integral)
print "Ang_vel: " + str(ang_vel)
print "Target angle: " + str(degrees(target))
if abs(error) < 0.01: #old threshold =0.006
integral = 0
ang_vel = 0
i += 1
publish_cmd_vel(0,ang_vel)
last_error = error
print "---"
if i >= 5:
target_achieved = True
rate.sleep()
tries += 1
if tries >= 1000:
target_achieved = True
print "Giving up"
publish_cmd_vel(0,0)
def moveBreak(target_x,target_y):
(trans, rot) = check_camera()
x_init = trans[0]
y_init = trans[1]
points = []
total_x = target_x-x_init
total_y = target_y-y_init
distance = sqrt((total_x)**2+(total_y)**2)
step = 1
d = step
while d < distance:
step_x = (d*total_x)/distance
step_y = (d*total_y)/distance
x = x_init + step_x
y = y_init + step_y
points.append([x,y])
d += step
points.append([target_x,target_y])
print points
return points
def move2goal():
(trans, rot) = check_camera()
current_x = trans[0]
current_y = trans[1]
target_x = input("Set your x: ")
target_y = input("Set your y: ")
points = moveBreak(target_x,target_y)
for point in points:
point_x = point[0]
point_y = point[1]
(trans, rot) = check_camera()
current_x = trans[0]
current_y = trans[1]
direction = atan2((point_y-current_y),(point_x-current_x))
print degrees(direction)
rotateTo(direction)
sleep(2)
(trans, rot) = check_camera()
current_x = trans[0]
current_y = trans[1]
movement_distance = sqrt((point_x-current_x)**2+(point_y-current_y)**2)
moveTo(movement_distance)
while not rospy.is_shutdown():
print check_camera()
move2goal()