-
Notifications
You must be signed in to change notification settings - Fork 1
/
mover
executable file
·356 lines (278 loc) · 13.1 KB
/
mover
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
#! usr/bin/env python3
"""
Motion planning and execution for Baxter arms
Services:
- '/reset'
- '/get_pose'
- '/go_to_pose'
- '/go_to_pose_left'
- '/get_joint_angles'
- '/go_to_joint_angle'
"""
import sys
import numpy as np
import rospy
import baxter_interface
from baxter_interface import CHECK_VERSION
import moveit_commander
from geometry_msgs.msg import Pose, PoseStamped, Point
from moveit_commander.conversions import pose_to_list, list_to_pose
from std_srvs.srv import Empty, EmptyResponse
from motion.srv import GoToPose, GoToPoseResponse, GetPose, GetPoseResponse
from sensor_msgs.msg import JointState
from tf.transformations import quaternion_from_euler, euler_from_quaternion
CYAN = '\033[96m'
class Mover(object):
"""
Mover node
On startup, enables robot and puts arms in neutral pose.
Provides service for arms to move to different poses.
"""
def __init__(self):
# Moveit initialization
self.robot = moveit_commander.RobotCommander()
self.scene = moveit_commander.PlanningSceneInterface()
# Arm groups
self.left_arm_group = moveit_commander.MoveGroupCommander("left_arm", wait_for_servers=30)
self.right_arm_group = moveit_commander.MoveGroupCommander("right_arm", wait_for_servers=30)
# Baxter interface limb
self.right_arm_limb = baxter_interface.limb.Limb("right")
# Reset Service
rospy.Service('/reset', Empty, self.reset_callback)
rospy.wait_for_service('/reset')
self.reset = rospy.ServiceProxy('/reset', Empty)
# GetPose service
rospy.Service('/get_pose', GetPose, self.get_pose_callback)
# GoToPose service
rospy.Service('/go_to_pose', GoToPose, self.go_to_pose_callback)
rospy.wait_for_service('/go_to_pose')
self.go_to_pose = rospy.ServiceProxy('/go_to_pose', GoToPose)
#Get_Joint_Angles Service
rospy.Service('/get_joint_angles', Empty, self.get_joint_angles_callback)
#Go to Joint angle service
rospy.Service('/go_to_joint_angle',Empty, self.move_to_joint)
#Go to Pose service for left arm
rospy.Service('/go_to_pose_left', GoToPose, self.go_to_pose_left_callback)
rospy.wait_for_service('/go_to_pose_left')
self.go_to_pose_left = rospy.ServiceProxy('/go_to_pose_left', GoToPose)
# Enable Robot
print("Getting robot state... ")
self._rs = baxter_interface.RobotEnable(CHECK_VERSION)
self._init_state = self._rs.state().enabled
print("Enabling robot... ")
self._rs.enable()
self.planning_frame_left = self.left_arm_group.get_planning_frame() # Planning frame: world
self.planning_frame_right = self.right_arm_group.get_planning_frame()
# Make right arm to go neutral position
print(f"{CYAN}Going to neutral pose...")
self.reset()
# Add cylinder around baxter head in planning scene
self.add_cylinder()
def wait_for_state_update(self, item_name, item_attached=False,
item_known=False, timeout=4):
"""
Ensures collision updates are received by waiting until changes
are reflected in get_attached_objects() and
get_known_object_names() lists.
Taken from Interbotix MoveIt Tutorial's Python interface example.
Args:
item_name (string): name of item being added to planning scene
item_attached (bool): whether item is already in
get_attached_objects()
item_known (bool): whether item is already in
get_known_object_names()
timeout (int): time limit if item can't be added
"""
start = rospy.get_time()
seconds = rospy.get_time()
while (seconds - start < timeout) and not rospy.is_shutdown():
attached_objects = self.scene.get_attached_objects([item_name])
is_attached = len(attached_objects.keys()) > 0
is_known = item_name in self.scene.get_known_object_names()
if (item_attached == is_attached) and (item_known == is_known):
return True
rospy.sleep(0.1)
seconds = rospy.get_time()
return False
def add_cylinder(self):
"""
Adds a cylinder around the Baxter head to prevent arms from colliding with the screen.
"""
cylinder_pose = PoseStamped()
cylinder_pose.pose.position.z = 0.7
cylinder_pose.header.frame_id = self.planning_frame_right
self.scene.add_cylinder('cylinder', cylinder_pose, 0.3, 0.2)
while not self.wait_for_state_update('cylinder', item_known=True):
self.scene.add_cylinder('cylinder', cylinder_pose, .3, 0.2)
def get_pose_callback(self, req):
"""
Reads the current pose of the right arm gripper
"""
right_current_pose = self.right_arm_group.get_current_pose(end_effector_link="right_gripper").pose
angles = euler_from_quaternion([right_current_pose.orientation.x,
right_current_pose.orientation.y,
right_current_pose.orientation.z,
right_current_pose.orientation.w])
return GetPoseResponse(x=right_current_pose.position.x,
y=right_current_pose.position.y,
z=right_current_pose.position.z,
r=angles[0], p=angles[1], yaw=angles[2])
def get_joint_angles_callback(self, req):
"""
Reads the current joint angles and prints them
"""
right_current_angles = self.right_arm_group.get_current_joint_values()
print(right_current_angles)
return Empty
def cartesian_plan_execute(self,move_group,target_pose):
"""
Plans and executes trajectory to bring arm to a target pose (for temperature reading)
Procedure:
1. Plans cartesian trajectory to target pose
2. If planner is able to plan less than 90% of the path to the target,
go to a saved postion
From that saved position, plan and execute movement
3. Otherwise, execute the plan
Args:
move_group (MoveGroupCommander): right or left arm move group
target_pose (Pose)
Returns:
fraction: fraction of final trajectory planned
"""
def planning(pose):
"""
Plans a cartesian path for a pose
Args:
pose (Pose)
Returns:
plan: cartesian trajectory
fraction: fraction of trajectory to target planned
"""
plan,fraction = move_group.compute_cartesian_path(
[pose],
0.01,
0.0
)
return plan, fraction
# Plan target pose
plan, fraction = planning(target_pose)
print(f"{CYAN} First Plan: {fraction} ")
if fraction<0.90:
# Person on left side
if target_pose.position.y <0:
print(f"Going to left saved position") #Tucked
angles = [0.3508981052287884, -0.6312330942148477, -0.13882526130362993, 2.0447963902512565, -0.1729563338340804, -1.119805975156352, 0.10584467436409355]
# Person on right side
else:
print(f"Going to right saved position") #Tucked
angles = [1.24674288535387, -0.6615292147755847, 1.0200972239438002, 0.7363107781849986, 0.8153107887610974, -1.14473316295949, 1.4143302864303515]
names = self.right_arm_limb.joint_names()
positions = dict(zip(names,angles))
self.right_arm_limb.move_to_joint_positions(positions)
plan, fraction = planning(target_pose)
print(f"{CYAN}\n Second Plan:{fraction}")
print(f"{CYAN}First attempt to target pose\n")
self.right_arm_group.execute(plan)
self.right_arm_group.stop()
else:
print(f"{CYAN}\nTrajectory Planned:{fraction}")
print(f"{CYAN}First attempt to target pose\n")
self.right_arm_group.execute(plan)
self.right_arm_group.stop()
self.right_arm_group.clear_pose_targets()
return fraction
def move_to_joint(self, req):
"""
Moves the right arm to the neutral position a
This is used in state machine to move the right arm back to a neutral position
Args:
req (EmptyRequest)
Returns:
EmptyResponse
"""
# Going to neutral position
joint_target_pose = self.right_arm_group.get_current_joint_values()
joint_target_pose[0] = 0.0 #1.3203739631723699
joint_target_pose[1] = -0.55 #-0.6626797003664987
joint_target_pose[2] = 0.0 #-0.3090971287589109
joint_target_pose[3] = 0.75 #1.23255356306593
joint_target_pose[4] = 0.0 #0.7485826244880819
joint_target_pose[5] = 1.26 #-0.6312330942148477
joint_target_pose[6] = 0.0 #2.6599226861933074
self.right_arm_group.set_joint_value_target(joint_target_pose)
success, traj, _, errCode = self.right_arm_group.plan()
ref = self.right_arm_group.get_current_pose()
traj = self.right_arm_group.retime_trajectory(ref,traj)
self.right_arm_group.execute(traj)
self.right_arm_group.clear_pose_target(end_effector_link="right_gripper")
return EmptyResponse()
def reset_callback(self, req):
"""
Moves the right arm to a default home state using baxter interface
We use the baxter interface instead of moveit because this method is produces as quicker
action from the robot, and since this is only called at startup, it will not interfere with
moveit commands used later.
Args:
req (EmptyRequest)
Returns:
EmtpyResponse
"""
self.right_arm_limb.move_to_neutral()
return EmptyResponse()
def go_to_pose_callback(self, req):
print(f"{CYAN} Go to pose called!")
"""
Callback funtion for the go_to_pose service. Takes the transforms/ coordinates from the vision package and directs the arm to go to the coordinates
Args:
req (arm_move/GoToPoseRequest): Target pose information
Returns:
(arm_move/GoToPoseResponse): Bool to indicate success or failure
"""
pose_goal = PoseStamped()
pose_goal.header.frame_id = req.frame
pose_goal.pose.position.x = req.x
pose_goal.pose.position.y = req.y
pose_goal.pose.position.z = req.z - 0.1 # 10cm lower so that thermometer is closer to face
quat = quaternion_from_euler(req.r, req.p, req.yaw)
pose_goal.pose.orientation.x = quat[0]
pose_goal.pose.orientation.y = quat[1]
pose_goal.pose.orientation.z = quat[2]
pose_goal.pose.orientation.w = quat[3]
print(f"{CYAN}x:{pose_goal.pose.position.x},y:{pose_goal.pose.position.y}")
fraction = self.cartesian_plan_execute(self.right_arm_group,pose_goal.pose)
return GoToPoseResponse(success=fraction > 0.50)
def go_to_pose_left_callback(self, req):
"""
Callback funtion for the go_to_pose_left service. Takes the transforms/ coordinates from the vision package and directs the arm to go to the coordinates
Args:
req (arm_move/GoToPoseRequest):
Returns:
(arm_move/GoToPoseResponse): Bool to indicate success or failure
"""
print(f"{CYAN} Go to pose called!")
pose_goal = PoseStamped()
pose_goal.header.frame_id = req.frame
pose_goal.pose.position.x = req.x
pose_goal.pose.position.y = req.y
pose_goal.pose.position.z = req.z
quat = quaternion_from_euler(req.r, req.p, req.yaw)
pose_goal.pose.orientation.x = quat[0]
pose_goal.pose.orientation.y = quat[1]
pose_goal.pose.orientation.z = quat[2]
pose_goal.pose.orientation.w = quat[3]
print(f"{CYAN}x:{pose_goal.pose.position.x},y:{pose_goal.pose.position.y}")
fraction = self.cartesian_plan_execute(self.left_arm_group,pose_goal.pose)
return GoToPoseResponse(success=fraction > 0.50)
def main():
"""
The main function
"""
moveit_commander.roscpp_initialize(sys.argv)
rospy.init_node('moveit_mover')
m = Mover()
rospy.spin()
if __name__ == '__main__':
try:
main()
except rospy.ROSInterruptException:
pass