forked from isaac-sim/IsaacGymEnvs
-
Notifications
You must be signed in to change notification settings - Fork 2
/
IndustRealTaskGearsInsert.yaml
116 lines (98 loc) · 4.92 KB
/
IndustRealTaskGearsInsert.yaml
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
# See schema in factory_schema_config_task.py for descriptions of common parameters.
defaults:
- IndustRealBase
- _self_
# - /factory_schema_config_task
name: IndustRealTaskGearsInsert
physics_engine: ${..physics_engine}
env:
numEnvs: 128
numObservations: 24
numStates: 47
numActions: 6
gear_medium_pos_offset: [-0.05, -0.02, 0.03]
num_gripper_move_sim_steps: 120 # number of timesteps to reserve for moving gripper before first step of episode
num_gripper_close_sim_steps: 60 # number of timesteps to reserve for closing gripper onto gear during each reset
base_pos_obs_noise: [0.001, 0.001, 0.0]
base_rot_obs_noise: [0.0, 0.0, 0.0]
randomize:
franka_arm_initial_dof_pos: [-1.7574766278484677, 0.8403247702305783, 2.015877580177467, -2.0924931236718334, -0.7379389376686856, 1.6256438760537268, 1.2689337870766628]
fingertip_centered_pos_initial: [0.0, 0.0, 0.2] # initial position of midpoint between fingertips above table
fingertip_centered_pos_noise: [0.0, 0.0, 0.0] # noise on fingertip pos
fingertip_centered_rot_initial: [3.141593, 0.0, 0.0] # initial rotation of fingertips (Euler)
fingertip_centered_rot_noise: [0.0, 0.0, 0.0] # noise on fingertip rotation
base_pos_xy_initial: [0.5, 0.0, 1.0781] # initial position of gear base on table
base_pos_xy_noise: [0.1, 0.1, 0.0381] # noise on gear base position
base_pos_z_noise_bounds: [0.0, 0.05] # noise on gear base offset from table
gear_pos_xyz_noise: [0.01, 0.01, 0.0] # noise on gear position
gear_rot_noise: 0.0872665 # noise on gear rotation
rl:
pos_action_scale: [0.01, 0.01, 0.01]
rot_action_scale: [0.01, 0.01, 0.01]
force_action_scale: [1.0, 1.0, 1.0]
torque_action_scale: [1.0, 1.0, 1.0]
unidirectional_rot: True # constrain Franka Z-rot to be unidirectional
unidirectional_force: False # constrain Franka Z-force to be unidirectional (useful for debugging)
clamp_rot: True
clamp_rot_thresh: 1.0e-6
num_keypoints: 4 # number of keypoints used in reward
keypoint_scale: 0.5 # length of line of keypoints
max_episode_length: 128
# SAPU
interpen_thresh: 0.001 # max allowed interpenetration between gear and shaft
# SDF-Based Reward
sdf_reward_scale: 10.0
sdf_reward_num_samples: 5000
# SBC
initial_max_disp: 0.01 # max initial downward displacement of gear at beginning of curriculum
curriculum_success_thresh: 0.6 # success rate threshold for increasing curriculum difficulty
curriculum_failure_thresh: 0.3 # success rate threshold for decreasing curriculum difficulty
curriculum_height_step: [-0.005, 0.002] # how much to increase max initial downward displacement after hitting success or failure thresh
curriculum_height_bound: [-0.005, 0.015] # max initial downward displacement of gear at hardest and easiest stages of curriculum
# Success bonus
close_error_thresh: 0.1 # threshold distance below which gear is considered close to shaft
success_height_thresh: 0.01 # threshold distance below which gear is considered successfully inserted
engagement_bonus: 10.0 # bonus if gear is engaged (partially inserted) with shaft
ctrl:
ctrl_type: task_space_impedance # {gym_default,
# joint_space_ik, joint_space_id,
# task_space_impedance, operational_space_motion,
# open_loop_force, closed_loop_force,
# hybrid_force_motion}
all:
jacobian_type: geometric
gripper_prop_gains: [500, 500]
gripper_deriv_gains: [2, 2]
gym_default:
ik_method: dls
joint_prop_gains: [40, 40, 40, 40, 40, 40, 40]
joint_deriv_gains: [8, 8, 8, 8, 8, 8, 8]
gripper_prop_gains: [500, 500]
gripper_deriv_gains: [20, 20]
joint_space_ik:
ik_method: dls
joint_prop_gains: [1, 1, 1, 1, 1, 1, 1]
joint_deriv_gains: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
joint_space_id:
ik_method: dls
joint_prop_gains: [40, 40, 40, 40, 40, 40, 40]
joint_deriv_gains: [8, 8, 8, 8, 8, 8, 8]
task_space_impedance:
motion_ctrl_axes: [1, 1, 1, 1, 1, 1]
task_prop_gains: [300, 300, 600, 50, 50, 50]
task_deriv_gains: [34, 34, 34, 1.4, 1.4, 1.4]
operational_space_motion:
motion_ctrl_axes: [1, 1, 1, 1, 1, 1]
task_prop_gains: [20, 20, 100, 0, 0, 100]
task_deriv_gains: [1, 1, 1, 1, 1, 1]
open_loop_force:
force_ctrl_axes: [0, 0, 1, 0, 0, 0]
closed_loop_force:
force_ctrl_axes: [0, 0, 1, 0, 0, 0]
wrench_prop_gains: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1]
hybrid_force_motion:
motion_ctrl_axes: [1, 1, 0, 1, 1, 1]
task_prop_gains: [40, 40, 40, 40, 40, 40]
task_deriv_gains: [8, 8, 8, 8, 8, 8]
force_ctrl_axes: [0, 0, 1, 0, 0, 0]
wrench_prop_gains: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1]