-
Notifications
You must be signed in to change notification settings - Fork 44
/
legged_robot_config.py
executable file
·256 lines (230 loc) · 9.85 KB
/
legged_robot_config.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
# License: see [LICENSE, LICENSES/legged_gym/LICENSE]
from params_proto.neo_proto import PrefixProto, ParamsProto
class Cfg(PrefixProto, cli=False):
class env(PrefixProto, cli=False):
num_envs = 4096
num_observations = 235
num_privileged_obs = 18
privileged_future_horizon = 1
num_actions = 12
num_observation_history = 15
env_spacing = 3. # not used with heightfields/trimeshes
send_timeouts = True # send time out information to the algorithm
episode_length_s = 20 # episode length in seconds
observe_vel = True
observe_only_ang_vel = False
observe_only_lin_vel = False
observe_yaw = False
observe_command = True
record_video = True
priv_observe_friction = True
priv_observe_restitution = True
priv_observe_base_mass = True
priv_observe_com_displacement = True
priv_observe_motor_strength = True
priv_observe_Kp_factor = True
priv_observe_Kd_factor = True
class terrain(PrefixProto, cli=False):
mesh_type = 'trimesh' # "heightfield" # none, plane, heightfield or trimesh
horizontal_scale = 0.1 # [m]
vertical_scale = 0.005 # [m]
border_size = 0 # 25 # [m]
curriculum = True
static_friction = 1.0
dynamic_friction = 1.0
restitution = 0.0
terrain_noise_magnitude = 0.1
# rough terrain only:
terrain_smoothness = 0.005
measure_heights = True
# 1mx1.6m rectangle (without center line)
measured_points_x = [-0.8, -0.7, -0.6, -0.5, -0.4, -0.3, -0.2, -0.1, 0., 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7, 0.8]
measured_points_y = [-0.5, -0.4, -0.3, -0.2, -0.1, 0., 0.1, 0.2, 0.3, 0.4, 0.5]
selected = False # select a unique terrain type and pass all arguments
terrain_kwargs = None # Dict of arguments for selected terrain
min_init_terrain_level = 0
max_init_terrain_level = 5 # starting curriculum state
terrain_length = 8.
terrain_width = 8.
num_rows = 10 # number of terrain rows (levels)
num_cols = 20 # number of terrain cols (types)
# terrain types: [smooth slope, rough slope, stairs up, stairs down, discrete]
terrain_proportions = [0.1, 0.1, 0.35, 0.25, 0.2]
# trimesh only:
slope_treshold = 0.75 # slopes above this threshold will be corrected to vertical surfaces
difficulty_scale = 1.
x_init_range = 1.
y_init_range = 1.
x_init_offset = 0.
y_init_offset = 0.
teleport_robots = True
teleport_thresh = 2.0
max_platform_height = 0.2
class commands(PrefixProto, cli=False):
command_curriculum = False
max_reverse_curriculum = 1.
max_forward_curriculum = 1.
forward_curriculum_threshold = 0.8
yaw_command_curriculum = False
max_yaw_curriculum = 1.
yaw_curriculum_threshold = 0.5
num_commands = 4
resampling_time = 10. # time before command are changed[s]
heading_command = True # if true: compute ang vel command from heading error
global_reference = False
num_lin_vel_bins = 20
lin_vel_step = 0.3
num_ang_vel_bins = 20
ang_vel_step = 0.3
distribution_update_extension_distance = 1
curriculum_seed = 100
# class ranges(ParamsProto, cli=False, prefix="commands.ranges"):
lin_vel_x = [-1.0, 1.0] # min max [m/s]
lin_vel_y = [-1.0, 1.0] # min max [m/s]
ang_vel_yaw = [-1, 1] # min max [rad/s]
body_height_cmd = [-0.05, 0.05]
impulse_height_commands = False
limit_vel_x = [-10.0, 10.0]
limit_vel_y = [-0.6, 0.6]
limit_vel_yaw = [-10.0, 10.0]
heading = [-3.14, 3.14]
class init_state(PrefixProto, cli=False):
pos = [0.0, 0.0, 1.] # x,y,z [m]
rot = [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
lin_vel = [0.0, 0.0, 0.0] # x,y,z [m/s]
ang_vel = [0.0, 0.0, 0.0] # x,y,z [rad/s]
# target angles when action = 0.0
default_joint_angles = {"joint_a": 0., "joint_b": 0.}
class control(PrefixProto, cli=False):
control_type = 'P' # P: position, V: velocity, T: torques
# PD Drive parameters:
stiffness = {'joint_a': 10.0, 'joint_b': 15.} # [N*m/rad]
damping = {'joint_a': 1.0, 'joint_b': 1.5} # [N*m*s/rad]
# action scale: target angle = actionScale * action + defaultAngle
action_scale = 0.5
hip_scale_reduction = 1.0
# decimation: Number of control action updates @ sim DT per policy DT
decimation = 4
class asset(PrefixProto, cli=False):
file = ""
foot_name = "None" # name of the feet bodies, used to index body state and contact force tensors
penalize_contacts_on = []
terminate_after_contacts_on = []
disable_gravity = False
# merge bodies connected by fixed joints. Specific fixed joints can be kept by adding " <... dont_collapse="true">
collapse_fixed_joints = True
fix_base_link = False # fixe the base of the robot
default_dof_drive_mode = 3 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 3 effort)
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
# replace collision cylinders with capsules, leads to faster/more stable simulation
replace_cylinder_with_capsule = True
flip_visual_attachments = True # Some .obj meshes must be flipped from y-up to z-up
density = 0.001
angular_damping = 0.
linear_damping = 0.
max_angular_velocity = 1000.
max_linear_velocity = 1000.
armature = 0.
thickness = 0.01
class domain_rand(PrefixProto, cli=False):
rand_interval_s = 10
randomize_friction = True
friction_range = [0.5, 1.25] # increase range
randomize_restitution = False
restitution_range = [0, 1.0]
randomize_base_mass = False
# add link masses, increase range, randomize inertia, randomize joint properties
added_mass_range = [-1., 1.]
randomize_com_displacement = False
# add link masses, increase range, randomize inertia, randomize joint properties
com_displacement_range = [-0.15, 0.15]
randomize_motor_strength = False
motor_strength_range = [0.9, 1.1]
randomize_Kp_factor = False
Kp_factor_range = [0.8, 1.3]
randomize_Kd_factor = False
Kd_factor_range = [0.5, 1.5]
push_robots = True
push_interval_s = 15
max_push_vel_xy = 1.
class rewards(PrefixProto, cli=False):
only_positive_rewards = True # if true negative total rewards are clipped at zero (avoids early termination problems)
tracking_sigma = 0.25 # tracking reward = exp(-error^2/sigma)
tracking_sigma_lat = 0.25 # tracking reward = exp(-error^2/sigma)
tracking_sigma_long = 0.25 # tracking reward = exp(-error^2/sigma)
tracking_sigma_yaw = 0.25 # tracking reward = exp(-error^2/sigma)
soft_dof_pos_limit = 1. # percentage of urdf limits, values above this limit are penalized
soft_dof_vel_limit = 1.
soft_torque_limit = 1.
base_height_target = 1.
max_contact_force = 100. # forces above this value are penalized
use_terminal_body_height = False
terminal_body_height = 0.20
class scales(ParamsProto, cli=False, prefix="rewards.scales"):
termination = -0.0
tracking_lin_vel = 1.0
tracking_ang_vel = 0.5
lin_vel_z = -2.0
ang_vel_xy = -0.05
orientation = -0.
torques = -0.00001
dof_vel = -0.
dof_acc = -2.5e-7
base_height = -0.
feet_air_time = 1.0
collision = -1.
feet_stumble = -0.0
action_rate = -0.01
stand_still = -0.
tracking_lin_vel_lat = 0.
tracking_lin_vel_long = 0.
class normalization(PrefixProto, cli=False):
class obs_scales(PrefixProto, cli=False):
lin_vel = 2.0
ang_vel = 0.25
dof_pos = 1.0
dof_vel = 0.05
height_measurements = 5.0
body_height_cmd = 2.0
clip_observations = 100.
clip_actions = 100.
friction_range = [0.05, 4.5] # increase range
restitution_range = [0, 1.0]
added_mass_range = [-1., 3.]
com_displacement_range = [-0.1, 0.1]
motor_strength_range = [0.9, 1.1]
Kp_factor_range = [0.8, 1.3]
Kd_factor_range = [0.5, 1.5]
class noise(PrefixProto, cli=False):
add_noise = True
noise_level = 1.0 # scales other values
class noise_scales(PrefixProto, cli=False):
dof_pos = 0.01
dof_vel = 1.5
lin_vel = 0.1
ang_vel = 0.2
gravity = 0.05
height_measurements = 0.1
# viewer camera:
class viewer(PrefixProto, cli=False):
ref_env = 0
pos = [10, 0, 6] # [m]
lookat = [11., 5, 3.] # [m]
class sim(PrefixProto, cli=False):
dt = 0.005
substeps = 1
gravity = [0., 0., -9.81] # [m/s^2]
up_axis = 1 # 0 is y, 1 is z
use_gpu_pipeline = True
class physx(PrefixProto, cli=False):
num_threads = 10
solver_type = 1 # 0: pgs, 1: tgs
num_position_iterations = 4
num_velocity_iterations = 0
contact_offset = 0.01 # [m]
rest_offset = 0.0 # [m]
bounce_threshold_velocity = 0.5 # 0.5 [m/s]
max_depenetration_velocity = 1.0
max_gpu_contact_pairs = 2 ** 23 # 2**24 -> needed for 8000 envs and more
default_buffer_size_multiplier = 5
contact_collection = 2 # 0: never, 1: last sub-step, 2: all sub-steps (default=2)