forked from vision-agh/apse_uav
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathkitchen.py
306 lines (235 loc) · 11.9 KB
/
kitchen.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
import argparse
import math
import os
import platform
import time
import numpy as np
from sklearn.preprocessing import normalize
from cv2 import aruco
from func_timeout import func_timeout
from unitree import *
from zmqRemoteApi import RemoteAPIClient
parser = argparse.ArgumentParser(description='Name of the config file')
parser.add_argument('--config', type=str,
help='config file', default="kitchen.yaml")
args = parser.parse_args()
model = ModelConfig.from_yaml_file(args.config)
if platform.system() == "Linux" and model.setup.use_unitree_arm_interface:
import unitree_arm_interface
armState = unitree_arm_interface.ArmFSMState
setup = model.setup
coppelia_config = model.capturing.coppelia
draw_settings = setup.draw_settings
config = model.capturing
aruco_dict = aruco.getPredefinedDictionary(aruco.DICT_4X4_50)
markerLength = config.marker_length # real size of the marker in metres
parameters = setArucoParameters() # create Aruco detection parameters
mtx, dist = readCameraParams(config) # read camera parameters
[cx1_prev, cy1_prev, cx2_prev, cy2_prev, cx3_prev, cy3_prev, cx4_prev, cy4_prev, cx5_prev, cy5_prev] = np.zeros(10,
dtype='int') # initialization of ArUco marker centres
if config.use_images:
k = config.frames.start
config.frames.end = len(os.listdir(config.path_input_images)) if config.frames.end is None else config.frames.end
frame = cv2.imread(config.path_input_images + "/image_%04d.jpg" % config.frames.start)
elif config.use_video:
video = cv2.VideoCapture(config.path_input_video)
k = config.frames.start
if config.frames.start >= 1 and video.isOpened():
for i in range(config.frames.start):
ret, frame = video.read()
if ret == False:
break
config.frames.end = np.inf if config.frames.end is None else config.frames.end
height, width, channels = frame.shape
fov = 60.0
focal_length = width / (2 * np.tan(fov * np.pi / 360))
mtx = np.array([[focal_length, 0, width / 2],
[0, focal_length, height / 2],
[0, 0, 1]])
dist = None
client = RemoteAPIClient()
try:
sim = func_timeout(3, lambda: client.getObject('sim'))
except:
raise IOError("Failed to connect to Coppeliasim, either open it or set setup.use_coppelia_sim to false")
if setup.reset_sim:
sim.stopSimulation()
while sim.getSimulationState() != sim.simulation_stopped:
time.sleep(0.1)
sim.loadScene(os.getcwd() + config.coppelia_path)
visionSensor, baseBoard, baseBoardCorner, yokeBoard, yokeBoardCorner, gripperBoard, \
gripperBoardCorner, tip, yoke_joint0, yoke_joint1, yoke_handle, target_handle, \
tip_world, yoke_world, base_world, joints, z1_robot, \
robot_parent, yoke_parent, forward, start = standard_coppelia_objects(sim)
if setup.reset_sim:
initial_coppelia(sim, baseBoard, yokeBoard, visionSensor, coppelia_config, gripperBoard, tip, yoke_joint0, yoke_joint1)
# Run a simulation in stepping mode:
# client.setStepping(True)
# sim.startSimulation()
# client.step()
# iterate over frames
started = False
while k <= config.frames.end and (config.use_images or (config.use_video and video.isOpened())):
# read frame from image or video
if config.use_images:
frame = cv2.imread(config.path_input_images + "/image_%04d.jpg" % k)
elif config.use_video:
ret, frame = video.read()
if ret == False:
break
# convert image to grayscale and detect Aruco markers
gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
charuco_board: BoardCoordinates = detect_charuco_board(config, gray, aruco_dict, parameters)
if charuco_board.is_ids_null_or_zero():
continue
cv2.aruco.drawDetectedMarkers(frame, charuco_board.corners, charuco_board.ids)
aruco.drawDetectedCornersCharuco(frame, charuco_board.base_corners, charuco_board.base_ids)
charuco_board = charuco_board.sort_corners()
base_obj_points, base_img_points = match_image_charuco_points(charuco_board)
base_flag, base_rvecs, base_tvecs, base_reproj_error = \
cv2.solvePnPGeneric(base_obj_points, base_img_points, mtx, dist, flags=cv2.SOLVEPNP_IPPE)
obj_points, img_points = match_image_charuco_points(charuco_board)
#charuco base to set camera position
base_rvec, base_tvec = pick_rvec_board(base_rvecs, base_tvecs)
cv2.drawFrameAxes(frame, mtx, dist, base_rvec, base_tvec, 1, thickness=5)
base_rvec_inv, base_tvec_inv = invert_vec(base_rvec, base_tvec)
camera_w = sim.getObjectPosition(visionSensor, -1)
base_board_corner_w = sim.getObjectPosition(baseBoardCorner, -1)
camera_bb = sim.getObjectPosition(visionSensor, baseBoardCorner)
camera_bb_pose = sim.getObjectPose(visionSensor, baseBoardCorner)
camera_bb_orient = sim.getObjectOrientation(visionSensor, baseBoardCorner)
cam_orient_coppelia = [base_rvec_inv[0][0] , base_rvec_inv[1][0], np.pi + base_rvec_inv[2][0]]
camera_location_coppelia = [base_tvec_inv[0][0], base_tvec_inv[1][0], base_tvec_inv[2][0]]
sim.setObjectPosition(visionSensor, baseBoardCorner, camera_location_coppelia)
sim.setObjectOrientation(visionSensor, baseBoardCorner, cam_orient_coppelia)
#yoke board to camera
yoke_board_corners, yoke_obj_points, yoke_img_points, yoke_board = \
create_grid_board(config, aruco_dict, gray, charuco_board.corners, charuco_board.ids, mtx, dist, config.grid_start, config.grid_end)
yoke_flag, yoke_rvecs, yoke_tvecs, yoke_r2 = cv2.solvePnPGeneric(
yoke_obj_points, yoke_img_points, mtx, dist,
flags=cv2.SOLVEPNP_IPPE)
yoke_rvec, yoke_tvec = pick_rvec_board(yoke_rvecs, yoke_tvecs)
cv2.drawFrameAxes(frame, mtx, dist, yoke_rvec, yoke_tvec, 1)
yoke_rvec_b, yoke_tvec_b = relative_position(base_rvec, base_tvec, yoke_rvec, yoke_tvec)
yoke_rvec_b2, yoke_tvec_b2 = relative_position(yoke_rvec, yoke_tvec,base_rvec, base_tvec, )
yoke_joint_w = sim.getJointPosition(yoke_joint1)
old_angle = sim.getJointPosition(yoke_joint1)
sim.setJointPosition(yoke_joint1, .0)
yoke_parent_bb = sim.getObjectPosition(yoke_parent, baseBoardCorner)
#step 1
yoke_parent_coppelia = [yoke_tvec_b2[0][0], yoke_tvec_b2[1][0], yoke_tvec_b2[2][0]]
sim.setObjectPosition(yoke_parent, baseBoardCorner, yoke_parent_coppelia)
#step 2
sim.setJointPosition(yoke_joint1, yoke_rvec_b[2][0])
#once i rotate the joint i know how much the
# yoke_joint0 needs to move
# relative to yoke_parent
#step 3
yoke_parent_yb = sim.getObjectPosition(yoke_parent, yokeBoardCorner)
sim.setObjectPosition(yoke_parent, yoke_parent, yoke_parent_yb)
# sim.setObjectPosition(z1_robot, gripperBoardCorner, [0, 0, 0])
gripper_board_corners, gripper_obj_points, gripper_img_points, gripper_board = \
create_grid_board(config, aruco_dict, gray, charuco_board.corners, charuco_board.ids, mtx, dist, config.gripper, config.gripper + 1)
gripper_flag, gripper_rvecs, gripper_tvecs, ggripper_r2 = cv2.solvePnPGeneric(
gripper_obj_points, gripper_img_points, mtx, dist,
flags=cv2.SOLVEPNP_IPPE)
gripper_rvec, gripper_tvec = pick_rvec_board(gripper_rvecs, gripper_tvecs)
cv2.drawFrameAxes(frame, mtx, dist, gripper_rvec, gripper_tvec, 1)
robot_base_position_1270_yokeboard=[ 0.23278, 0.21795, 0.31225]
gripperboard_tip = sim.getObjectPosition(gripperBoardCorner, tip)
for i in range(6):
sim.setJointPosition(joints[i], 0)
sim.setJointTargetPosition(joints[i], 0)
gripper_rvec_b, gripper_tvec_b = relative_position(base_rvec, base_tvec, gripper_rvec, gripper_tvec)
gripper_rvec_b2, gripper_tvec_b2 = relative_position(gripper_rvec, gripper_tvec, base_rvec, base_tvec)
# should be the same at calib
gripper_board_bb = sim.getObjectPosition(gripperBoardCorner, baseBoardCorner)
robot_parent_bb = sim.getObjectPosition(robot_parent, baseBoardCorner)
#step 1
gripper_parent_coppelia = [gripper_tvec_b2[0][0], gripper_tvec_b2[1][0], gripper_tvec_b2[2][0]]
sim.setObjectPosition(robot_parent, baseBoardCorner, gripper_parent_coppelia)
starting_joint_positions = [1.497, 1.51, -0.72, -0.654, -1.035, 0.]
for i in range(6):
sim.setJointPosition(joints[i], starting_joint_positions[i])
#robot ik doesnt work from start, move to forward
# sim.setJointPosition(joints[1], 45 / 180 * np.pi)
# sim.setJointPosition(joints[2], -45 / 180 * np.pi)
#forward2 is 10cm from forward to test that IK doesn't crash
# forward2 = sim.getObject('/forward2')
# forward2_w = sim.getObjectPosition(forward2, -1)
# sim.setObjectPosition(target_handle, -1, forward2_w)
simIK, ikEnv, ikGroup, ikElement, simToIkMap, something = create_ik(client, z1_robot, tip, target_handle)
result, flags, precision = sync_ik(simIK, ikEnv, ikGroup)
# ik_target = '/IK'
# robotBaseHandle = sim.getObject(ik_target)
# scriptHandle = sim.getScript(sim.scripttype_customizationscript, robotBaseHandle)
# sim.callScriptFunction('handleIK', scriptHandle)
yoke_rb = sim.getObjectPosition(yoke_world, base_world)
yoke_rb_ori = sim.getObjectOrientation(yoke_world, base_world)
yoke_rb_pose = sim.getObjectPose(yoke_world, base_world)
yoke_world_90 = sim.getObject('/yoke_world_90')
yoke_rb_pose_90 = sim.getObjectPose(yoke_world_90, base_world)
start_pose = sim.getObjectPose(start, base_world)
# make sure all coordinates are in robot base so i can send them to the real robot
sim.setObjectPose(target_handle, base_world, yoke_rb_pose_90)
# sim.setObjectPose(target_handle, base_world, start_pose)
result, flags, precision = sync_ik(simIK, ikEnv, ikGroup)
screenshot_from_coppeliasim(sim, visionSensor, k, parameters)
sim.setJointPosition(yoke_joint1, 0)
yoke_handle_pos = sim.getObjectPosition(yoke_handle, -1)
sim.setObjectPosition(target_handle, -1, yoke_handle_pos)
starting_joint_positions = [1.497, 1.51, -0.72, -0.654, -1.035, 0.]
for i in range(6):
sim.setJointPosition(joints[i], starting_joint_positions[i])
stops = draw_circle(sim, yoke_joint1, yoke_handle, target_handle, joints)
stops[0, 8:14] = [43.633202600357095] * 6
traj = create_traj(stops)
start = np.zeros((2, 15))
start[0, 1:7] = [0.00009, 0.00321, -0.00536, -0.06671, 0.00200, 0.00095]
start[1] = traj[0]
starting_traj = create_traj(start, 3)
final_traj = np.vstack((starting_traj, traj))
np.savetxt("circular_movement.csv", final_traj, delimiter=",")
# setup robot
if not started:
arm = connect_to_arm(model)
started = True
joint_positions = get_joint_positions(sim, joints)
# gripper
# joint_positions.append(0)
# Robot rotates the yoke
if k == 1272:
sim.setJointPosition(yoke_joint1, yoke_rvec_b[2][0])
yoke_handle_pos = sim.getObjectPosition(yoke_handle, -1)
sim.setObjectPosition(target_handle, -1, yoke_handle_pos)
result, flags, precision = sync_ik(simIK, ikEnv, ikGroup)
joint_positions = get_joint_positions(sim, joints)
move_arm(arm, joint_positions)
else:
move_arm(arm, starting_joint_positions, -0.6)
move_arm(arm, joint_positions, -0.2)
arm.loopOn()
arm.startTrack(armState.JOINTCTRL)
move_gripper(arm, 0) # Close the gripper
#arm.backToStart()
#arm.loopOff()
if setup.use_coppelia_sim:
client.step()
# show results on image
if setup.show_image:
cv2.namedWindow("Detection result", cv2.WINDOW_NORMAL)
cv2.imshow("Detection result", frame)
if cv2.waitKey(1) & 0xFF == ord('q'):
break
# increment frame number
k = k + config.frames.step
# skip frames from video
if config.use_video:
for i in range(config.frames.step - 1):
ret, frame = video.read()
if ret == False:
break
if config.use_video:
video.release()
if setup.show_image:
cv2.destroyAllWindows()