-
Notifications
You must be signed in to change notification settings - Fork 218
/
factory_task_nut_bolt_pick.py
806 lines (661 loc) · 30.6 KB
/
factory_task_nut_bolt_pick.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
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
# Copyright (c) 2018-2023, NVIDIA Corporation
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice, this
# list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
"""Factory: Class for nut-bolt pick task.
Inherits nut-bolt environment class and abstract task class (not enforced). Can be executed with
PYTHON_PATH omniisaacgymenvs/scripts/rlgames_train.py task=FactoryTaskNutBoltPick
"""
import asyncio
import hydra
import omegaconf
import torch
import omni.kit
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.torch.transformations import tf_combine
from typing import Tuple
import omni.isaac.core.utils.torch as torch_utils
import omniisaacgymenvs.tasks.factory.factory_control as fc
from omniisaacgymenvs.tasks.factory.factory_env_nut_bolt import FactoryEnvNutBolt
from omniisaacgymenvs.tasks.factory.factory_schema_class_task import FactoryABCTask
from omniisaacgymenvs.tasks.factory.factory_schema_config_task import (
FactorySchemaConfigTask,
)
class FactoryTaskNutBoltPick(FactoryEnvNutBolt, FactoryABCTask):
def __init__(self, name, sim_config, env, offset=None) -> None:
"""Initialize environment superclass. Initialize instance variables."""
super().__init__(name, sim_config, env)
self._get_task_yaml_params()
def _get_task_yaml_params(self) -> None:
"""Initialize instance variables from YAML files."""
cs = hydra.core.config_store.ConfigStore.instance()
cs.store(name="factory_schema_config_task", node=FactorySchemaConfigTask)
self.cfg_task = omegaconf.OmegaConf.create(self._task_cfg)
self.max_episode_length = (
self.cfg_task.rl.max_episode_length
) # required instance var for VecTask
asset_info_path = "../tasks/factory/yaml/factory_asset_info_nut_bolt.yaml" # relative to Gym's Hydra search path (cfg dir)
self.asset_info_nut_bolt = hydra.compose(config_name=asset_info_path)
self.asset_info_nut_bolt = self.asset_info_nut_bolt[""][""][""]["tasks"][
"factory"
][
"yaml"
] # strip superfluous nesting
ppo_path = "train/FactoryTaskNutBoltPickPPO.yaml" # relative to Gym's Hydra search path (cfg dir)
self.cfg_ppo = hydra.compose(config_name=ppo_path)
self.cfg_ppo = self.cfg_ppo["train"] # strip superfluous nesting
def post_reset(self) -> None:
"""Reset the world. Called only once, before simulation begins."""
if self.cfg_task.sim.disable_gravity:
self.disable_gravity()
self.acquire_base_tensors()
self._acquire_task_tensors()
self.refresh_base_tensors()
self.refresh_env_tensors()
self._refresh_task_tensors()
# Reset all envs
indices = torch.arange(self._num_envs, dtype=torch.int64, device=self._device)
asyncio.ensure_future(
self.reset_idx_async(indices, randomize_gripper_pose=False)
)
def _acquire_task_tensors(self) -> None:
"""Acquire tensors."""
# Grasp pose tensors
nut_grasp_heights = self.bolt_head_heights + self.nut_heights * 0.5 # nut COM
self.nut_grasp_pos_local = nut_grasp_heights * torch.tensor(
[0.0, 0.0, 1.0], device=self.device
).repeat((self.num_envs, 1))
self.nut_grasp_quat_local = (
torch.tensor([0.0, 0.0, 1.0, 0.0], device=self.device)
.unsqueeze(0)
.repeat(self.num_envs, 1)
)
# Keypoint tensors
self.keypoint_offsets = (
self._get_keypoint_offsets(self.cfg_task.rl.num_keypoints)
* self.cfg_task.rl.keypoint_scale
)
self.keypoints_gripper = torch.zeros(
(self.num_envs, self.cfg_task.rl.num_keypoints, 3),
dtype=torch.float32,
device=self.device,
)
self.keypoints_nut = torch.zeros_like(
self.keypoints_gripper, device=self.device
)
self.identity_quat = (
torch.tensor([1.0, 0.0, 0.0, 0.0], device=self.device)
.unsqueeze(0)
.repeat(self.num_envs, 1)
)
self.actions = torch.zeros(
(self.num_envs, self.num_actions), device=self.device
)
def pre_physics_step(self, actions) -> None:
"""Reset environments. Apply actions from policy. Simulation step called after this method."""
if not self.world.is_playing():
return
env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(env_ids) > 0:
self.reset_idx(env_ids, randomize_gripper_pose=True)
self.actions = actions.clone().to(
self.device
) # shape = (num_envs, num_actions); values = [-1, 1]
self._apply_actions_as_ctrl_targets(
actions=self.actions,
ctrl_target_gripper_dof_pos=self.asset_info_franka_table.franka_gripper_width_max,
do_scale=True,
)
async def pre_physics_step_async(self, actions) -> None:
"""Reset environments. Apply actions from policy. Simulation step called after this method."""
if not self.world.is_playing():
return
env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(env_ids) > 0:
await self.reset_idx_async(env_ids, randomize_gripper_pose=True)
self.actions = actions.clone().to(
self.device
) # shape = (num_envs, num_actions); values = [-1, 1]
self._apply_actions_as_ctrl_targets(
actions=self.actions,
ctrl_target_gripper_dof_pos=self.asset_info_franka_table.franka_gripper_width_max,
do_scale=True,
)
def reset_idx(self, env_ids, randomize_gripper_pose) -> None:
"""Reset specified environments."""
self._reset_franka(env_ids)
self._reset_object(env_ids)
if randomize_gripper_pose:
self._randomize_gripper_pose(
env_ids, sim_steps=self.cfg_task.env.num_gripper_move_sim_steps
)
self._reset_buffers(env_ids)
async def reset_idx_async(self, env_ids, randomize_gripper_pose) -> None:
"""Reset specified environments."""
self._reset_franka(env_ids)
self._reset_object(env_ids)
if randomize_gripper_pose:
await self._randomize_gripper_pose_async(
env_ids, sim_steps=self.cfg_task.env.num_gripper_move_sim_steps
)
self._reset_buffers(env_ids)
def _reset_franka(self, env_ids) -> None:
"""Reset DOF states and DOF targets of Franka."""
self.dof_pos[env_ids] = torch.cat(
(
torch.tensor(
self.cfg_task.randomize.franka_arm_initial_dof_pos,
device=self.device,
),
torch.tensor(
[self.asset_info_franka_table.franka_gripper_width_max],
device=self.device,
),
torch.tensor(
[self.asset_info_franka_table.franka_gripper_width_max],
device=self.device,
),
),
dim=-1,
) # shape = (num_envs, num_dofs)
self.dof_vel[env_ids] = 0.0 # shape = (num_envs, num_dofs)
self.ctrl_target_dof_pos[env_ids] = self.dof_pos[env_ids]
indices = env_ids.to(dtype=torch.int32)
self.frankas.set_joint_positions(self.dof_pos[env_ids], indices=indices)
self.frankas.set_joint_velocities(self.dof_vel[env_ids], indices=indices)
def _reset_object(self, env_ids) -> None:
"""Reset root states of nut and bolt."""
# Randomize root state of nut
nut_noise_xy = 2 * (
torch.rand((self.num_envs, 2), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
nut_noise_xy = nut_noise_xy @ torch.diag(
torch.tensor(self.cfg_task.randomize.nut_pos_xy_noise, device=self.device)
)
self.nut_pos[env_ids, 0] = (
self.cfg_task.randomize.nut_pos_xy_initial[0] + nut_noise_xy[env_ids, 0]
)
self.nut_pos[env_ids, 1] = (
self.cfg_task.randomize.nut_pos_xy_initial[1] + nut_noise_xy[env_ids, 1]
)
self.nut_pos[
env_ids, 2
] = self.cfg_base.env.table_height - self.bolt_head_heights.squeeze(-1)
self.nut_quat[env_ids, :] = torch.tensor(
[1.0, 0.0, 0.0, 0.0], dtype=torch.float32, device=self.device
).repeat(len(env_ids), 1)
self.nut_linvel[env_ids, :] = 0.0
self.nut_angvel[env_ids, :] = 0.0
indices = env_ids.to(dtype=torch.int32)
self.nuts.set_world_poses(
self.nut_pos[env_ids] + self.env_pos[env_ids],
self.nut_quat[env_ids],
indices,
)
self.nuts.set_velocities(
torch.cat((self.nut_linvel[env_ids], self.nut_angvel[env_ids]), dim=1),
indices,
)
# Randomize root state of bolt
bolt_noise_xy = 2 * (
torch.rand((self.num_envs, 2), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
bolt_noise_xy = bolt_noise_xy @ torch.diag(
torch.tensor(self.cfg_task.randomize.bolt_pos_xy_noise, device=self.device)
)
self.bolt_pos[env_ids, 0] = (
self.cfg_task.randomize.bolt_pos_xy_initial[0] + bolt_noise_xy[env_ids, 0]
)
self.bolt_pos[env_ids, 1] = (
self.cfg_task.randomize.bolt_pos_xy_initial[1] + bolt_noise_xy[env_ids, 1]
)
self.bolt_pos[env_ids, 2] = self.cfg_base.env.table_height
self.bolt_quat[env_ids, :] = torch.tensor(
[1.0, 0.0, 0.0, 0.0], dtype=torch.float32, device=self.device
).repeat(len(env_ids), 1)
indices = env_ids.to(dtype=torch.int32)
self.bolts.set_world_poses(
self.bolt_pos[env_ids] + self.env_pos[env_ids],
self.bolt_quat[env_ids],
indices,
)
def _reset_buffers(self, env_ids) -> None:
"""Reset buffers."""
self.reset_buf[env_ids] = 0
self.progress_buf[env_ids] = 0
def _apply_actions_as_ctrl_targets(
self, actions, ctrl_target_gripper_dof_pos, do_scale
) -> None:
"""Apply actions from policy as position/rotation/force/torque targets."""
# Interpret actions as target pos displacements and set pos target
pos_actions = actions[:, 0:3]
if do_scale:
pos_actions = pos_actions @ torch.diag(
torch.tensor(self.cfg_task.rl.pos_action_scale, device=self.device)
)
self.ctrl_target_fingertip_midpoint_pos = (
self.fingertip_midpoint_pos + pos_actions
)
# Interpret actions as target rot (axis-angle) displacements
rot_actions = actions[:, 3:6]
if do_scale:
rot_actions = rot_actions @ torch.diag(
torch.tensor(self.cfg_task.rl.rot_action_scale, device=self.device)
)
# Convert to quat and set rot target
angle = torch.norm(rot_actions, p=2, dim=-1)
axis = rot_actions / angle.unsqueeze(-1)
rot_actions_quat = torch_utils.quat_from_angle_axis(angle, axis)
if self.cfg_task.rl.clamp_rot:
rot_actions_quat = torch.where(
angle.unsqueeze(-1).repeat(1, 4) > self.cfg_task.rl.clamp_rot_thresh,
rot_actions_quat,
torch.tensor([1.0, 0.0, 0.0, 0.0], device=self.device).repeat(
self.num_envs, 1
),
)
self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_mul(
rot_actions_quat, self.fingertip_midpoint_quat
)
if self.cfg_ctrl["do_force_ctrl"]:
# Interpret actions as target forces and target torques
force_actions = actions[:, 6:9]
if do_scale:
force_actions = force_actions @ torch.diag(
torch.tensor(
self.cfg_task.rl.force_action_scale, device=self.device
)
)
torque_actions = actions[:, 9:12]
if do_scale:
torque_actions = torque_actions @ torch.diag(
torch.tensor(
self.cfg_task.rl.torque_action_scale, device=self.device
)
)
self.ctrl_target_fingertip_contact_wrench = torch.cat(
(force_actions, torque_actions), dim=-1
)
self.ctrl_target_gripper_dof_pos = ctrl_target_gripper_dof_pos
self.generate_ctrl_signals()
def post_physics_step(
self,
) -> Tuple[torch.Tensor, torch.Tensor, torch.Tensor, torch.Tensor]:
"""Step buffers. Refresh tensors. Compute observations and reward. Reset environments."""
self.progress_buf[:] += 1
if self.world.is_playing():
# In this policy, episode length is constant
is_last_step = self.progress_buf[0] == self.max_episode_length - 1
if is_last_step:
# At this point, robot has executed RL policy. Now close gripper and lift (open-loop)
if self.cfg_task.env.close_and_lift:
self._close_gripper(
sim_steps=self.cfg_task.env.num_gripper_close_sim_steps
)
self._lift_gripper(
franka_gripper_width=0.0,
lift_distance=0.3,
sim_steps=self.cfg_task.env.num_gripper_lift_sim_steps,
)
self.refresh_base_tensors()
self.refresh_env_tensors()
self._refresh_task_tensors()
self.get_observations()
self.get_states()
self.calculate_metrics()
self.get_extras()
return self.obs_buf, self.rew_buf, self.reset_buf, self.extras
async def post_physics_step_async(self):
"""Step buffers. Refresh tensors. Compute observations and reward. Reset environments."""
self.progress_buf[:] += 1
if self.world.is_playing():
# In this policy, episode length is constant
is_last_step = self.progress_buf[0] == self.max_episode_length - 1
if self.cfg_task.env.close_and_lift:
# At this point, robot has executed RL policy. Now close gripper and lift (open-loop)
if is_last_step:
await self._close_gripper_async(
sim_steps=self.cfg_task.env.num_gripper_close_sim_steps
)
await self._lift_gripper_async(
sim_steps=self.cfg_task.env.num_gripper_lift_sim_steps
)
self.refresh_base_tensors()
self.refresh_env_tensors()
self._refresh_task_tensors()
self.get_observations()
self.get_states()
self.calculate_metrics()
self.get_extras()
return self.obs_buf, self.rew_buf, self.reset_buf, self.extras
def _refresh_task_tensors(self):
"""Refresh tensors."""
# Compute pose of nut grasping frame
self.nut_grasp_quat, self.nut_grasp_pos = tf_combine(
self.nut_quat,
self.nut_pos,
self.nut_grasp_quat_local,
self.nut_grasp_pos_local,
)
# Compute pos of keypoints on gripper and nut in world frame
for idx, keypoint_offset in enumerate(self.keypoint_offsets):
self.keypoints_gripper[:, idx] = tf_combine(
self.fingertip_midpoint_quat,
self.fingertip_midpoint_pos,
self.identity_quat,
keypoint_offset.repeat(self.num_envs, 1),
)[1]
self.keypoints_nut[:, idx] = tf_combine(
self.nut_grasp_quat,
self.nut_grasp_pos,
self.identity_quat,
keypoint_offset.repeat(self.num_envs, 1),
)[1]
def get_observations(self) -> dict:
"""Compute observations."""
# Shallow copies of tensors
obs_tensors = [
self.fingertip_midpoint_pos,
self.fingertip_midpoint_quat,
self.fingertip_midpoint_linvel,
self.fingertip_midpoint_angvel,
self.nut_grasp_pos,
self.nut_grasp_quat,
]
self.obs_buf = torch.cat(
obs_tensors, dim=-1
) # shape = (num_envs, num_observations)
observations = {self.frankas.name: {"obs_buf": self.obs_buf}}
return observations
def calculate_metrics(self) -> None:
"""Update reward and reset buffers."""
self._update_reset_buf()
self._update_rew_buf()
def _update_reset_buf(self) -> None:
"""Assign environments for reset if successful or failed."""
# If max episode length has been reached
self.reset_buf[:] = torch.where(
self.progress_buf[:] >= self.max_episode_length - 1,
torch.ones_like(self.reset_buf),
self.reset_buf,
)
def _update_rew_buf(self) -> None:
"""Compute reward at current timestep."""
keypoint_reward = -self._get_keypoint_dist()
action_penalty = (
torch.norm(self.actions, p=2, dim=-1)
* self.cfg_task.rl.action_penalty_scale
)
self.rew_buf[:] = (
keypoint_reward * self.cfg_task.rl.keypoint_reward_scale
- action_penalty * self.cfg_task.rl.action_penalty_scale
)
# In this policy, episode length is constant across all envs
is_last_step = self.progress_buf[0] == self.max_episode_length - 1
if is_last_step:
# Check if nut is picked up and above table
lift_success = self._check_lift_success(height_multiple=3.0)
self.rew_buf[:] += lift_success * self.cfg_task.rl.success_bonus
self.extras["successes"] = torch.mean(lift_success.float())
def _get_keypoint_offsets(self, num_keypoints) -> torch.Tensor:
"""Get uniformly-spaced keypoints along a line of unit length, centered at 0."""
keypoint_offsets = torch.zeros((num_keypoints, 3), device=self.device)
keypoint_offsets[:, -1] = (
torch.linspace(0.0, 1.0, num_keypoints, device=self.device) - 0.5
)
return keypoint_offsets
def _get_keypoint_dist(self) -> torch.Tensor:
"""Get keypoint distance."""
keypoint_dist = torch.sum(
torch.norm(self.keypoints_nut - self.keypoints_gripper, p=2, dim=-1), dim=-1
)
return keypoint_dist
def _close_gripper(self, sim_steps=20) -> None:
"""Fully close gripper using controller. Called outside RL loop (i.e., after last step of episode)."""
self._move_gripper_to_dof_pos(gripper_dof_pos=0.0, sim_steps=sim_steps)
def _move_gripper_to_dof_pos(self, gripper_dof_pos, sim_steps=20) -> None:
"""Move gripper fingers to specified DOF position using controller."""
delta_hand_pose = torch.zeros(
(self.num_envs, 6), device=self.device
) # No hand motion
self._apply_actions_as_ctrl_targets(
delta_hand_pose, gripper_dof_pos, do_scale=False
)
# Step sim
for _ in range(sim_steps):
SimulationContext.step(self.world, render=True)
def _lift_gripper(
self, franka_gripper_width=0.0, lift_distance=0.3, sim_steps=20
) -> None:
"""Lift gripper by specified distance. Called outside RL loop (i.e., after last step of episode)."""
delta_hand_pose = torch.zeros([self.num_envs, 6], device=self.device)
delta_hand_pose[:, 2] = lift_distance
# Step sim
for _ in range(sim_steps):
self._apply_actions_as_ctrl_targets(
delta_hand_pose, franka_gripper_width, do_scale=False
)
SimulationContext.step(self.world, render=True)
async def _close_gripper_async(self, sim_steps=20) -> None:
"""Fully close gripper using controller. Called outside RL loop (i.e., after last step of episode)."""
await self._move_gripper_to_dof_pos_async(
gripper_dof_pos=0.0, sim_steps=sim_steps
)
async def _move_gripper_to_dof_pos_async(
self, gripper_dof_pos, sim_steps=20
) -> None:
"""Move gripper fingers to specified DOF position using controller."""
delta_hand_pose = torch.zeros(
(self.num_envs, self.cfg_task.env.numActions), device=self.device
) # No hand motion
self._apply_actions_as_ctrl_targets(
delta_hand_pose, gripper_dof_pos, do_scale=False
)
# Step sim
for _ in range(sim_steps):
await omni.kit.app.get_app().next_update_async()
async def _lift_gripper_async(
self, franka_gripper_width=0.0, lift_distance=0.3, sim_steps=20
) -> None:
"""Lift gripper by specified distance. Called outside RL loop (i.e., after last step of episode)."""
delta_hand_pose = torch.zeros([self.num_envs, 6], device=self.device)
delta_hand_pose[:, 2] = lift_distance
# Step sim
for _ in range(sim_steps):
self._apply_actions_as_ctrl_targets(
delta_hand_pose, franka_gripper_width, do_scale=False
)
await omni.kit.app.get_app().next_update_async()
def _check_lift_success(self, height_multiple) -> torch.Tensor:
"""Check if nut is above table by more than specified multiple times height of nut."""
lift_success = torch.where(
self.nut_pos[:, 2]
> self.cfg_base.env.table_height
+ self.nut_heights.squeeze(-1) * height_multiple,
torch.ones((self.num_envs,), device=self.device),
torch.zeros((self.num_envs,), device=self.device),
)
return lift_success
def _randomize_gripper_pose(self, env_ids, sim_steps) -> None:
"""Move gripper to random pose."""
# step once to update physx with the newly set joint positions from reset_franka()
SimulationContext.step(self.world, render=True)
# Set target pos above table
self.ctrl_target_fingertip_midpoint_pos = torch.tensor(
[0.0, 0.0, self.cfg_base.env.table_height], device=self.device
) + torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_pos_initial, device=self.device
)
self.ctrl_target_fingertip_midpoint_pos = (
self.ctrl_target_fingertip_midpoint_pos.unsqueeze(0).repeat(
self.num_envs, 1
)
)
fingertip_midpoint_pos_noise = 2 * (
torch.rand((self.num_envs, 3), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
fingertip_midpoint_pos_noise = fingertip_midpoint_pos_noise @ torch.diag(
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_pos_noise, device=self.device
)
)
self.ctrl_target_fingertip_midpoint_pos += fingertip_midpoint_pos_noise
# Set target rot
ctrl_target_fingertip_midpoint_euler = (
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_rot_initial,
device=self.device,
)
.unsqueeze(0)
.repeat(self.num_envs, 1)
)
fingertip_midpoint_rot_noise = 2 * (
torch.rand((self.num_envs, 3), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
fingertip_midpoint_rot_noise = fingertip_midpoint_rot_noise @ torch.diag(
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_rot_noise, device=self.device
)
)
ctrl_target_fingertip_midpoint_euler += fingertip_midpoint_rot_noise
self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz(
ctrl_target_fingertip_midpoint_euler[:, 0],
ctrl_target_fingertip_midpoint_euler[:, 1],
ctrl_target_fingertip_midpoint_euler[:, 2],
)
# Step sim and render
for _ in range(sim_steps):
if not self.world.is_playing():
return
self.refresh_base_tensors()
self.refresh_env_tensors()
self._refresh_task_tensors()
pos_error, axis_angle_error = fc.get_pose_error(
fingertip_midpoint_pos=self.fingertip_midpoint_pos,
fingertip_midpoint_quat=self.fingertip_midpoint_quat,
ctrl_target_fingertip_midpoint_pos=self.ctrl_target_fingertip_midpoint_pos,
ctrl_target_fingertip_midpoint_quat=self.ctrl_target_fingertip_midpoint_quat,
jacobian_type=self.cfg_ctrl["jacobian_type"],
rot_error_type="axis_angle",
)
delta_hand_pose = torch.cat((pos_error, axis_angle_error), dim=-1)
actions = torch.zeros(
(self.num_envs, self.cfg_task.env.numActions), device=self.device
)
actions[:, :6] = delta_hand_pose
self._apply_actions_as_ctrl_targets(
actions=actions,
ctrl_target_gripper_dof_pos=self.asset_info_franka_table.franka_gripper_width_max,
do_scale=False,
)
SimulationContext.step(self.world, render=True)
self.dof_vel[env_ids, :] = torch.zeros_like(self.dof_vel[env_ids])
indices = env_ids.to(dtype=torch.int32)
self.frankas.set_joint_velocities(self.dof_vel[env_ids], indices=indices)
# step once to update physx with the newly set joint velocities
SimulationContext.step(self.world, render=True)
async def _randomize_gripper_pose_async(self, env_ids, sim_steps) -> None:
"""Move gripper to random pose."""
# step once to update physx with the newly set joint positions from reset_franka()
await omni.kit.app.get_app().next_update_async()
# Set target pos above table
self.ctrl_target_fingertip_midpoint_pos = torch.tensor(
[0.0, 0.0, self.cfg_base.env.table_height], device=self.device
) + torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_pos_initial, device=self.device
)
self.ctrl_target_fingertip_midpoint_pos = (
self.ctrl_target_fingertip_midpoint_pos.unsqueeze(0).repeat(
self.num_envs, 1
)
)
fingertip_midpoint_pos_noise = 2 * (
torch.rand((self.num_envs, 3), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
fingertip_midpoint_pos_noise = fingertip_midpoint_pos_noise @ torch.diag(
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_pos_noise, device=self.device
)
)
self.ctrl_target_fingertip_midpoint_pos += fingertip_midpoint_pos_noise
# Set target rot
ctrl_target_fingertip_midpoint_euler = (
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_rot_initial,
device=self.device,
)
.unsqueeze(0)
.repeat(self.num_envs, 1)
)
fingertip_midpoint_rot_noise = 2 * (
torch.rand((self.num_envs, 3), dtype=torch.float32, device=self.device)
- 0.5
) # [-1, 1]
fingertip_midpoint_rot_noise = fingertip_midpoint_rot_noise @ torch.diag(
torch.tensor(
self.cfg_task.randomize.fingertip_midpoint_rot_noise, device=self.device
)
)
ctrl_target_fingertip_midpoint_euler += fingertip_midpoint_rot_noise
self.ctrl_target_fingertip_midpoint_quat = torch_utils.quat_from_euler_xyz(
ctrl_target_fingertip_midpoint_euler[:, 0],
ctrl_target_fingertip_midpoint_euler[:, 1],
ctrl_target_fingertip_midpoint_euler[:, 2],
)
# Step sim and render
for _ in range(sim_steps):
self.refresh_base_tensors()
self.refresh_env_tensors()
self._refresh_task_tensors()
pos_error, axis_angle_error = fc.get_pose_error(
fingertip_midpoint_pos=self.fingertip_midpoint_pos,
fingertip_midpoint_quat=self.fingertip_midpoint_quat,
ctrl_target_fingertip_midpoint_pos=self.ctrl_target_fingertip_midpoint_pos,
ctrl_target_fingertip_midpoint_quat=self.ctrl_target_fingertip_midpoint_quat,
jacobian_type=self.cfg_ctrl["jacobian_type"],
rot_error_type="axis_angle",
)
delta_hand_pose = torch.cat((pos_error, axis_angle_error), dim=-1)
actions = torch.zeros(
(self.num_envs, self.cfg_task.env.numActions), device=self.device
)
actions[:, :6] = delta_hand_pose
self._apply_actions_as_ctrl_targets(
actions=actions,
ctrl_target_gripper_dof_pos=self.asset_info_franka_table.franka_gripper_width_max,
do_scale=False,
)
await omni.kit.app.get_app().next_update_async()
self.dof_vel[env_ids, :] = torch.zeros_like(self.dof_vel[env_ids])
indices = env_ids.to(dtype=torch.int32)
self.frankas.set_joint_velocities(self.dof_vel[env_ids], indices=indices)
# step once to update physx with the newly set joint velocities
await omni.kit.app.get_app().next_update_async()