-
Notifications
You must be signed in to change notification settings - Fork 0
/
ur10_env.py
217 lines (171 loc) · 8.52 KB
/
ur10_env.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
import pybullet
import pybullet_data
import gym
import numpy as np
class UR10(gym.Env):
observation_space = gym.spaces.Dict(dict(
desired_goal=gym.spaces.Box(-np.inf, np.inf, shape=(3,), dtype='float32'),
achieved_goal=gym.spaces.Box(-np.inf, np.inf, shape=(3,), dtype='float32'),
observation=gym.spaces.Box(-np.inf, np.inf, shape=(25,), dtype='float32'),
))
action_space = gym.spaces.Box(low=-1, high=1, shape=(4,), dtype=float)
position_bounds = [(0.5, 1.0), (-0.25, 0.25), (0.7, 1)]
def __init__(self, is_train, is_dense=False):
self.connect(is_train)
pybullet.setAdditionalSearchPath(pybullet_data.getDataPath())
self.is_dense = is_dense
self.distance_threshold = 0.15
self.planeId = None
self.robot = None
self.joints = []
self.links = {}
self.step_id = None
self.object = None
self.initial_joint_values = np.array([1.0, 0.0, 1.0])
self.gripper_orientation = pybullet.getQuaternionFromEuler([np.pi, 0, 0])
self.joint_values = None
self.gripper_value = None
self.target_position = np.array([1, 0, 1])
def step(self, action):
self.step_id += 1
self.joint_values += np.array(action[:3]) * 0.1
self.joint_values = np.clip(self.joint_values, -1, 1)
self.gripper_value = 1 if action[3] > 0 else -1
# end effector points down, not up (in case useOrientation==1)
target_pos = self._rescale(self.joint_values, self.position_bounds)
self.move_hand(target_pos, self.gripper_orientation, self.gripper_value)
pybullet.stepSimulation()
object_pos, object_orient = pybullet.getBasePositionAndOrientation(self.object)
info = self.compute_info(action)
return self.compute_state(), self.compute_reward(object_pos, self.target_position, info), self.is_done(), info
def reset(self):
self._reset_world()
x_position = np.random.uniform(0.75, 1)
y_position = np.random.uniform(-0.25, 0.25)
# FIXME add rotation
orientation = pybullet.getQuaternionFromEuler([0, 0, np.pi / 2])
#self.object = pybullet.loadURDF('cube_small.urdf', [x_position, y_position, 0.6], orientation, globalScaling=0.75)
self.object = pybullet.loadURDF('random_urdfs/000/000.urdf', [x_position, y_position, 0.6], orientation, globalScaling=1)
pybullet.stepSimulation()
return self.compute_state()
def start_log_video(self, filename):
pybullet.startStateLogging(pybullet.STATE_LOGGING_VIDEO_MP4, filename)
def stop_log_video(self):
pybullet.stopStateLogging(pybullet.STATE_LOGGING_VIDEO_MP4)
def render(self, mode='human'):
pass
def __del__(self):
pybullet.disconnect()
def compute_state(self):
state = np.zeros(3 * 4 + 3 * 4 + 1)
gripper_position, gripper_orientation, _, _, _, _, gripper_velocity, gripper_angular_velocity = \
pybullet.getLinkState(self.robot, linkIndex=self.links['gripper_finger_joint'], computeLinkVelocity=True)
state[:3] = gripper_position
state[3:6] = pybullet.getEulerFromQuaternion(gripper_orientation)
state[6:9] = gripper_velocity
state[9:12] = gripper_angular_velocity
object_pos, object_orient = pybullet.getBasePositionAndOrientation(self.object)
object_velocity, object_angular_velocity = pybullet.getBaseVelocity(self.object)
state[12:15] = np.asarray(object_pos) - gripper_position
state[15:18] = pybullet.getEulerFromQuaternion(object_orient)
state[18:21] = object_velocity
state[21:24] = object_angular_velocity
state[24] = self.compute_gripper_position()
return {'observation': state, 'desired_goal': self.target_position, 'achieved_goal': object_pos}
def compute_reward(self, achieved_goal, desired_goal, info):
distance = np.linalg.norm(achieved_goal - desired_goal)
if self.is_dense:
gripper_position, gripper_orientation, _, _, _, _, gripper_velocity, gripper_angular_velocity = \
pybullet.getLinkState(self.robot, linkIndex=self.links['gripper_finger_joint'],
computeLinkVelocity=True)
gripper_distance = np.linalg.norm(achieved_goal - np.asarray(gripper_position))
return 1 - min(distance, 0.5) - gripper_distance
else:
return -(distance > self.distance_threshold).astype(np.float32)
def is_done(self):
object_pos, object_orient = pybullet.getBasePositionAndOrientation(self.object)
return self.step_id == 200 or np.linalg.norm(object_pos - np.array([1.0, 0.0, 0.6])) > 1.0
def compute_info(self, last_action):
object_pos, object_orient = pybullet.getBasePositionAndOrientation(self.object)
distance = np.linalg.norm(object_pos - self.target_position)
return {
'is_success': distance < self.distance_threshold,
'gripper_pos': self.compute_gripper_position(),
'last_action': last_action
}
def connect(self, is_train):
if is_train:
pybullet.connect(pybullet.DIRECT)
else:
pybullet.connect(pybullet.GUI)
def _rescale(self, values, bounds):
result = np.zeros_like(values)
for i, (value, (lower_bound, upper_bound)) in enumerate(zip(values, bounds)):
result[i] = (value + 1) / 2 * (upper_bound - lower_bound) + lower_bound
return result
def move_hand(self, target_position, orientation, gripper_value):
joint_poses = pybullet.calculateInverseKinematics(
self.robot,
10, # 'gripper_finger_joint'
target_position,
orientation,
maxNumIterations=100,
residualThreshold=.01
)
for joint_id in range(6):
pybullet.setJointMotorControl2(
self.robot, self.joints[joint_id]['jointID'],
pybullet.POSITION_CONTROL,
targetPosition=joint_poses[joint_id],
)
for joint_id in range(6, 12):
value = gripper_value
minval, maxval = self.joints[joint_id]['jointLowerLimit'], self.joints[joint_id]['jointUpperLimit']
value = (value + 1) / 2 * (maxval - minval) + minval
pybullet.setJointMotorControl2(
self.robot,
self.joints[joint_id]['jointID'],
pybullet.POSITION_CONTROL,
targetPosition=value,
)
def compute_gripper_position(self):
values = np.zeros(6)
for i, joint_id in enumerate(range(6, 12)):
data = pybullet.getJointState(self.robot, self.joints[joint_id]['jointID'])
position, velocity = data[:2]
lower_bound, upper_bound = self.joints[joint_id]['jointLowerLimit'], self.joints[joint_id]['jointUpperLimit']
values[i] = (position - lower_bound) / (upper_bound - lower_bound) * 2 - 1
return np.mean(values)
def _reset_world(self):
pybullet.resetSimulation()
pybullet.setGravity(0, 0, -10)
self.planeId = pybullet.loadURDF('plane.urdf')
robot_position = [0, 0, 1.0]
robot_orientation = pybullet.getQuaternionFromEuler([0, 0, 0])
self.robot = pybullet.loadURDF('ur10_robot.urdf', robot_position, robot_orientation)
joint_type = ['REVOLUTE', 'PRISMATIC', 'SPHERICAL', 'PLANAR', 'FIXED']
self.joints = []
self.links = {}
for joint_id in range(pybullet.getNumJoints(self.robot)):
info = pybullet.getJointInfo(self.robot, joint_id)
data = {
'jointID': info[0],
'jointName': info[1].decode('utf-8'),
'jointType': joint_type[info[2]],
'jointLowerLimit': info[8],
'jointUpperLimit': info[9],
'jointMaxForce': info[10],
'jointMaxVelocity': info[11]
}
if data['jointType'] != 'FIXED':
self.joints.append(data)
self.links[data['jointName']] = joint_id
self.step_id = 0
self.object = None
self.initial_joint_values = np.array([1.0, 0.0, 1.0])
self.gripper_orientation = pybullet.getQuaternionFromEuler([np.pi, 0, 0])
self.joint_values = self.initial_joint_values
self.gripper_value = -1
pybullet.loadURDF('table/table.urdf', globalScaling=1, basePosition=[0.5, 0, 0])
self.position_bounds = [(0.5, 1.0), (-0.25, 0.25), (0.7, 1)]
self.target_position = np.array([1, 0, 1])