forked from lihuang3/ur5_ROS-Gazebo
-
Notifications
You must be signed in to change notification settings - Fork 1
/
ur5_mp.py
executable file
·376 lines (273 loc) · 13.6 KB
/
ur5_mp.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
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
#!/usr/bin/env python
"""
moveit_cartesian_path.py - Version 0.1 2016-07-28
Based on the R. Patrick Goebel's moveit_cartesian_demo.py demo code.
Plan and execute a Cartesian path for the end-effector.
Created for the Pi Robot Project: http://www.pirobot.org
Copyright (c) 2014 Patrick Goebel. All rights reserved.
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.5
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details at:
http://www.gnu.org/licenses/gpl.html
"""
import rospy, sys, numpy as np
import moveit_commander
from copy import deepcopy
from geometry_msgs.msg import Twist
import moveit_msgs.msg
from sensor_msgs.msg import Image
from ur5_notebook.msg import Tracker
from std_msgs.msg import Header
from trajectory_msgs.msg import JointTrajectory
from trajectory_msgs.msg import JointTrajectoryPoint
from time import sleep
tracker = Tracker()
class ur5_mp:
def __init__(self):
rospy.init_node("ur5_mp", anonymous=False)
self.cxy_sub = rospy.Subscriber('cxy', Tracker, self.tracking_callback, queue_size=1)
self.cxy_pub = rospy.Publisher('cxy1', Tracker, queue_size=1)
self.phase = 1
self.object_cnt = 0
self.track_flag = False
self.default_pose_flag = True
self.cx = 400.0
self.cy = 400.0
self.points=[]
self.state_change_time = rospy.Time.now()
rospy.loginfo("Starting node moveit_cartesian_path")
rospy.on_shutdown(self.cleanup)
# Initialize the move_group API
moveit_commander.roscpp_initialize(sys.argv)
# Initialize the move group for the ur5_arm
self.arm = moveit_commander.MoveGroupCommander('manipulator')
# Get the name of the end-effector link
self.end_effector_link = self.arm.get_end_effector_link()
# Set the reference frame for pose targets
reference_frame = "/base_link"
# Set the ur5_arm reference frame accordingly
self.arm.set_pose_reference_frame(reference_frame)
# Allow replanning to increase the odds of a solution
self.arm.allow_replanning(True)
# Allow some leeway in position (meters) and orientation (radians)
self.arm.set_goal_position_tolerance(0.01)
self.arm.set_goal_orientation_tolerance(0.1)
self.arm.set_planning_time(0.1)
self.arm.set_max_acceleration_scaling_factor(.5)
self.arm.set_max_velocity_scaling_factor(.5)
# Get the current pose so we can add it as a waypoint
start_pose = self.arm.get_current_pose(self.end_effector_link).pose
# Initialize the waypoints list
self.waypoints= []
self.pointx = []
self.pointy = []
# Set the first waypoint to be the starting pose
# Append the pose to the waypoints list
wpose = deepcopy(start_pose)
# Set the next waypoint to the right 0.5 meters
wpose.position.x = -0.2
wpose.position.y = -0.2
wpose.position.z = 0.3
self.waypoints.append(deepcopy(wpose))
# wpose.position.x = 0.1052
# wpose.position.y = -0.4271
# wpose.position.z = 0.4005
#
# wpose.orientation.x = 0.4811
# wpose.orientation.y = 0.5070
# wpose.orientation.z = -0.5047
# wpose.orientation.w = 0.5000
# self.waypoints.append(deepcopy(wpose))
if np.sqrt((wpose.position.x-start_pose.position.x)**2+(wpose.position.x-start_pose.position.x)**2 \
+(wpose.position.x-start_pose.position.x)**2)<0.1:
rospy.loginfo("Warnig: target position overlaps with the initial position!")
# self.arm.set_pose_target(wpose)
# Specify default (idle) joint states
self.default_joint_states = self.arm.get_current_joint_values()
self.default_joint_states[0] = -1.57691
self.default_joint_states[1] = -1.71667
self.default_joint_states[2] = 1.79266
self.default_joint_states[3] = -1.67721
self.default_joint_states[4] = -1.5705
self.default_joint_states[5] = 0.0
self.arm.set_joint_value_target(self.default_joint_states)
# Set the internal state to the current state
self.arm.set_start_state_to_current_state()
plan = self.arm.plan()
self.arm.execute(plan)
# Specify end states (drop object)
self.end_joint_states = deepcopy(self.default_joint_states)
self.end_joint_states[0] = -3.65
# self.end_joint_states[1] = -1.3705
self.transition_pose = deepcopy(self.default_joint_states)
self.transition_pose[0] = -3.65
self.transition_pose[4] = -1.95
def cleanup(self):
rospy.loginfo("Stopping the robot")
# Stop any current arm movement
self.arm.stop()
#Shut down MoveIt! cleanly
rospy.loginfo("Shutting down Moveit!")
moveit_commander.roscpp_shutdown()
moveit_commander.os._exit(0)
def tracking_callback(self, msg):
self.track_flag = msg.flag1
self.cx = msg.x
self.cy = msg.y
self.error_x = msg.error_x
self.error_y = msg.error_y
if len(self.pointx)>9:
self.track_flag = True
if self.phase == 2:
self.track_flag = False
self.phase = 1
if (self.track_flag and -0.6 < self.waypoints[0].position.x and self.waypoints[0].position.x < 0.6):
self.execute()
self.default_pose_flag = False
else:
if not self.default_pose_flag:
self.track_flag = False
self.execute()
self.default_pose_flag = True
def execute(self):
if self.track_flag:
# Get the current pose so we can add it as a waypoint
start_pose = self.arm.get_current_pose(self.end_effector_link).pose
# Initialize the waypoints list
self.waypoints= []
# Set the first waypoint to be the starting pose
# Append the pose to the waypoints list
wpose = deepcopy(start_pose)
# wpose.position.x = -0.5215
# wpose.position.y = 0.2014
# wpose.position.z = 0.4102
if len(self.pointx)>8:
if len(self.pointx)==9:
x_speed = np.mean(np.asarray(self.pointx[4:8]) - np.asarray(self.pointx[3:7]))
wpose.position.x += 2 * x_speed
wpose.position.z = 0.05
else:
if len(self.pointx)==11:
tracker.flag2 = 1
self.cxy_pub.publish(tracker)
if len(self.pointx)<12:
x_speed = np.mean(np.asarray(self.pointx[4:8])-np.asarray(self.pointx[3:7]))
wpose.position.x += (x_speed-self.error_x*0.015/105)
else:
if tracker.flag2:
self.track_flag=False
transition_pose = deepcopy(start_pose)
transition_pose.position.z = 0.4000
self.waypoints.append(deepcopy(transition_pose))
self.arm.set_start_state_to_current_state()
plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.02, 0.0, True)
self.arm.execute(plan)
self.arm.set_max_acceleration_scaling_factor(.15)
self.arm.set_max_velocity_scaling_factor(.25)
self.arm.set_joint_value_target(self.transition_pose)
self.arm.set_start_state_to_current_state()
plan = self.arm.plan()
self.arm.execute(plan)
self.arm.set_joint_value_target(self.end_joint_states)
self.arm.set_start_state_to_current_state()
plan = self.arm.plan()
self.arm.execute(plan)
if -0.1+0.02*self.object_cnt<0.2:
self.object_cnt += 1
self.waypoints = []
start_pose = self.arm.get_current_pose(self.end_effector_link).pose
transition_pose = deepcopy(start_pose)
transition_pose.position.x -= 0.1
transition_pose.position.z = -0.1 + self.object_cnt*0.025
self.waypoints.append(deepcopy(transition_pose))
self.arm.set_start_state_to_current_state()
plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.02, 0.0, True)
self.arm.execute(plan)
self.phase = 2
tracker.flag2 = 0
self.cxy_pub.publish(tracker)
# Set the next waypoint to the right 0.5 meters
else:
wpose.position.x -= self.error_x*0.05/105
wpose.position.y += self.error_y*0.04/105
wpose.position.z = 0.15
#wpose.position.z = 0.4005
if self.phase == 1:
self.waypoints.append(deepcopy(wpose))
self.pointx.append(wpose.position.x)
self.pointy.append(wpose.position.y)
# Set the internal state to the current state
# self.arm.set_pose_target(wpose)
self.arm.set_start_state_to_current_state()
# Plan the Cartesian path connecting the waypoints
"""moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path(
self, waypoints, eef_step, jump_threshold, avoid_collisios= True)
Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the
poses specified as waypoints. Configurations are computed for every eef_step meters;
The jump_threshold specifies the maximum distance in configuration space between consecutive points
in the resultingpath. The return value is a tuple: a fraction of how much of the path was followed,
the actual RobotTrajectory.
"""
plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.01, 0.0, True)
# plan = self.arm.plan()
# If we have a complete plan, execute the trajectory
if 1-fraction < 0.2:
rospy.loginfo("Path computed successfully. Moving the arm.")
num_pts = len(plan.joint_trajectory.points)
rospy.loginfo("\n# intermediate waypoints = "+str(num_pts))
self.arm.execute(plan)
rospy.loginfo("Path execution complete.")
else:
rospy.loginfo("Path planning failed")
else:
# Get the current pose so we can add it as a waypoint
start_pose = self.arm.get_current_pose(self.end_effector_link).pose
# Initialize the waypoints list
self.waypoints= []
self.pointx = []
self.pointy = []
# Set the first waypoint to be the starting pose
# Append the pose to the waypoints list
wpose = deepcopy(start_pose)
# Set the next waypoint to the right 0.5 meters
wpose.position.x = 0.1052
wpose.position.y = -0.4271
wpose.position.z = 0.4005
wpose.orientation.x = 0.4811
wpose.orientation.y = 0.4994
wpose.orientation.z = -0.5121
wpose.orientation.w = 0.5069
self.pointx.append(wpose.position.x)
self.pointy.append(wpose.position.y)
self.waypoints.append(deepcopy(wpose))
# Set the internal state to the current state
# self.arm.set_pose_target(wpose)
self.arm.set_start_state_to_current_state()
# Plan the Cartesian path connecting the waypoints
"""moveit_commander.move_group.MoveGroupCommander.compute_cartesian_path(
self, waypoints, eef_step, jump_threshold, avoid_collisios= True)
Compute a sequence of waypoints that make the end-effector move in straight line segments that follow the
poses specified as waypoints. Configurations are computed for every eef_step meters;
The jump_threshold specifies the maximum distance in configuration space between consecutive points
in the resultingpath. The return value is a tuple: a fraction of how much of the path was followed,
the actual RobotTrajectory.
"""
plan, fraction = self.arm.compute_cartesian_path(self.waypoints, 0.01, 0.0, True)
# plan = self.arm.plan()
# If we have a complete plan, execute the trajectory
if 1-fraction < 0.2:
rospy.loginfo("Path computed successfully. Moving the arm.")
num_pts = len(plan.joint_trajectory.points)
rospy.loginfo("\n# intermediate waypoints = "+str(num_pts))
self.arm.execute(plan)
rospy.loginfo("Path execution complete.")
else:
rospy.loginfo("Path planning failed")
# print self.points
mp=ur5_mp()
rospy.spin()