Skip to content

Commit 8676010

Browse files
temp commit
Atlas imported and runs
1 parent 5b2d164 commit 8676010

File tree

7 files changed

+990
-31
lines changed

7 files changed

+990
-31
lines changed

isaacgymenvs/cfg/task/Atlas.yaml

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ name: Atlas
44
physics_engine: ${..physics_engine}
55

66
env:
7-
numEnvs: ${resolve_default:1024,${...num_envs}}
7+
numEnvs: ${resolve_default:16,${...num_envs}}
88
envSpacing: 4. # [m]
99

1010
clipObservations: 5.0
@@ -16,14 +16,14 @@ env:
1616
restitution: 0. # [-]
1717

1818
baseInitState:
19-
pos: [0.0, 0.0, 1.05] # x,y,z [m]
19+
pos: [0.0, 0.0, 0.95] # x,y,z [m]
2020
rot: [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
2121
vLinear: [0.0, 0.0, 0.0] # x,y,z [m/s]
2222
vAngular: [0.0, 0.0, 0.0] # x,y,z [rad/s]
2323

2424
randomCommandVelocityRanges:
25-
linear_x: [0., 0.] # min max [m/s]
26-
linear_y: [-2., 2.] # min max [m/s]
25+
linear_x: [-1., 1.] # min max [m/s]
26+
linear_y: [0., 0.] # min max [m/s]
2727
yaw: [-1.57, 1.57] # min max [rad/s]
2828

2929
control:
@@ -46,7 +46,7 @@ env:
4646

4747
urdfAsset:
4848
collapseFixedJoints: True
49-
fixBaseLink: True
49+
fixBaseLink: False
5050
defaultDofDriveMode: 1 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)
5151

5252
learn:
Lines changed: 151 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,151 @@
1+
# used to create the object
2+
name: AtlasTerrain
3+
4+
physics_engine: 'physx'
5+
6+
env:
7+
numEnvs: ${resolve_default:16,${...num_envs}}
8+
numObservations: 242
9+
numActions: 30
10+
envSpacing: 4. # [m]
11+
enableDebugVis: False
12+
13+
terrain:
14+
terrainType: plane # none, plane, or trimesh
15+
staticFriction: 1.0 # [-]
16+
dynamicFriction: 1.0 # [-]
17+
restitution: 0. # [-]
18+
# rough terrain only:
19+
curriculum: true
20+
maxInitMapLevel: 0
21+
mapLength: 8.
22+
mapWidth: 8.
23+
numLevels: 10
24+
numTerrains: 20
25+
# terrain types: [smooth slope, rough slope, stairs up, stairs down, discrete]
26+
terrainProportions: [0.1, 0.1, 0.35, 0.25, 0.2]
27+
# tri mesh only:
28+
slopeTreshold: 0.5
29+
30+
baseInitState:
31+
pos: [0.0, 0.0, 0.95] # x,y,z [m]
32+
rot: [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
33+
vLinear: [0.0, 0.0, 0.0] # x,y,z [m/s]
34+
vAngular: [0.0, 0.0, 0.0] # x,y,z [rad/s]
35+
36+
randomCommandVelocityRanges:
37+
# train
38+
linear_x: [0., 0.] # min max [m/s]
39+
linear_y: [-1., 1.] # min max [m/s]
40+
yaw: [-3.14, 3.14] # min max [rad/s]
41+
42+
control:
43+
# PD Drive parameters:
44+
stiffness: 85.0 # [N*m/rad]
45+
damping: 4.0 # [N*m*s/rad]
46+
# action scale: target angle = actionScale * action + defaultAngle
47+
actionScale: 3.14
48+
# decimation: Number of control action updates @ sim DT per policy DT
49+
decimation: 1
50+
51+
defaultJointAngles: # = target angles when action = 0.0
52+
LF_HAA: 0.03 # [rad]
53+
LH_HAA: 0.03 # [rad]
54+
RF_HAA: -0.03 # [rad]
55+
RH_HAA: -0.03 # [rad]
56+
57+
LF_HFE: 0.4 # [rad]
58+
LH_HFE: -0.4 # [rad]
59+
RF_HFE: 0.4 # [rad]
60+
RH_HFE: -0.4 # [rad]
61+
62+
LF_KFE: -0.8 # [rad]
63+
LH_KFE: 0.8 # [rad]
64+
RF_KFE: -0.8 # [rad]
65+
RH_KFE: 0.8 # [rad]
66+
67+
urdfAsset:
68+
file: "urdf/atlas/urdf/atlas_v4_with_multisense.urdf"
69+
footName: foot # SHANK if collapsing fixed joint, FOOT otherwise
70+
kneeName: glut
71+
collapseFixedJoints: true
72+
fixBaseLink: false
73+
defaultDofDriveMode: 1 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)
74+
75+
learn:
76+
allowKneeContacts: true
77+
# rewards
78+
terminalReward: 0.0
79+
linearVelocityXYRewardScale: 1.0
80+
linearVelocityZRewardScale: -4.0
81+
angularVelocityXYRewardScale: -0.05
82+
angularVelocityZRewardScale: 0.5
83+
orientationRewardScale: -0. #-1.
84+
torqueRewardScale: -0.00002 # -0.000025
85+
jointAccRewardScale: -0.0005 # -0.0025
86+
baseHeightRewardScale: -0.0 #5
87+
feetAirTimeRewardScale: 1.0
88+
kneeCollisionRewardScale: -0.25
89+
feetStumbleRewardScale: -0. #-2.0
90+
actionRateRewardScale: -0.01
91+
# cosmetics
92+
hipRewardScale: -0. #25
93+
94+
# normalization
95+
linearVelocityScale: 2.0
96+
angularVelocityScale: 0.25
97+
dofPositionScale: 1.0
98+
dofVelocityScale: 0.05
99+
heightMeasurementScale: 5.0
100+
101+
# noise
102+
addNoise: false
103+
noiseLevel: 1.0 # scales other values
104+
dofPositionNoise: 0.01
105+
dofVelocityNoise: 1.5
106+
linearVelocityNoise: 0.1
107+
angularVelocityNoise: 0.2
108+
gravityNoise: 0.05
109+
heightMeasurementNoise: 0.06
110+
111+
#randomization
112+
randomizeFriction: false
113+
frictionRange: [0.5, 1.25]
114+
pushRobots: false
115+
pushInterval_s: 15
116+
117+
# episode length in seconds
118+
episodeLength_s: 20
119+
120+
# viewer cam:
121+
viewer:
122+
refEnv: 0
123+
pos: [0, 0, 10] # [m]
124+
lookat: [1., 1, 9] # [m]
125+
126+
# set to True if you use camera sensors in the environment
127+
enableCameraSensors: False
128+
129+
sim:
130+
dt: 0.02
131+
substeps: 2
132+
up_axis: "z"
133+
use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
134+
gravity: [0.0, 0.0, -9.81]
135+
physx:
136+
num_threads: ${....num_threads}
137+
solver_type: ${....solver_type}
138+
use_gpu: ${contains:"cuda",${....sim_device}} # set to False to run on CPU
139+
num_position_iterations: 4
140+
num_velocity_iterations: 1
141+
contact_offset: 0.02
142+
rest_offset: 0.0
143+
bounce_threshold_velocity: 0.2
144+
max_depenetration_velocity: 100.0
145+
default_buffer_size_multiplier: 5.0
146+
max_gpu_contact_pairs: 8388608 # 8*1024*1024
147+
num_subscenes: ${....num_subscenes}
148+
contact_collection: 1 # 0: CC_NEVER (don't collect contact info), 1: CC_LAST_SUBSTEP (collect only contacts on last substep), 2: CC_ALL_SUBSTEPS (broken - do not use!)
149+
150+
task:
151+
randomize: False

isaacgymenvs/cfg/train/AtlasPPO.yaml

100755100644
Lines changed: 51 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,81 @@
11
params:
2-
32
seed: ${...seed}
43

54
algo:
6-
name: sac
5+
name: a2c_continuous
76

87
model:
9-
name: soft_actor_critic
8+
name: continuous_a2c_logstd
109

1110
network:
12-
name: soft_actor_critic
11+
name: actor_critic
1312
separate: True
13+
1414
space:
1515
continuous:
16+
mu_activation: None
17+
sigma_activation: None
18+
mu_init:
19+
name: default
20+
sigma_init:
21+
name: const_initializer
22+
val: 0. # std = 1.
23+
fixed_sigma: True
24+
1625
mlp:
17-
units: [256, 128, 64]
26+
units: [512] #, 256, 128]
1827
activation: elu
28+
d2rl: False
1929

2030
initializer:
2131
name: default
22-
log_std_bounds: [-5, 2]
32+
regularizer:
33+
name: None
34+
rnn:
35+
name: lstm
36+
units: 256 #128
37+
layers: 1
38+
before_mlp: False #True
39+
concat_input: True
40+
layer_norm: False
41+
2342

2443
load_checkpoint: ${if:${...checkpoint},True,False} # flag which sets whether to load the checkpoint
2544
load_path: ${...checkpoint} # path to the checkpoint to load
2645

2746
config:
28-
name: ${resolve_default:Bittle,${....experiment}}
47+
name: ${resolve_default:Atlas,${....experiment}}
2948
full_experiment_name: ${.name}
3049
env_name: rlgpu
50+
ppo: True
51+
mixed_precision: True
3152
normalize_input: True
53+
normalize_value: True
54+
normalize_advantage: True
55+
value_bootstrap: True
56+
clip_actions: False
57+
num_actors: ${....task.env.numEnvs}
3258
reward_shaper:
3359
scale_value: 1.0
34-
num_steps_per_episode: 8
3560
gamma: 0.99
36-
init_alpha: 1.0
37-
alpha_lr: 0.005
38-
actor_lr: 0.0005
39-
critic_lr: 0.0005
40-
critic_tau: 0.005
41-
batch_size: 8192
42-
learnable_temperature: true
43-
num_seed_steps: 5
44-
num_warmup_steps: 10
45-
replay_buffer_size: 1000000
46-
num_actors: ${....task.env.numEnvs}
61+
tau: 0.95
62+
e_clip: 0.2
63+
entropy_coef: 0.001
64+
learning_rate: 3.e-4 # overwritten by adaptive lr_schedule
65+
lr_schedule: adaptive
66+
kl_threshold: 0.008 # target kl for adaptive lr
67+
truncate_grads: True
68+
grad_norm: 1.
69+
horizon_length: 24
70+
minibatch_size: 16
71+
mini_epochs: 5
72+
critic_coef: 2
73+
clip_value: True
74+
seq_len: 4 # only for rnn
75+
bounds_loss_coef: 0.
4776

4877
max_epochs: ${resolve_default:1000,${....max_iterations}}
4978
save_best_after: 200
50-
save_frequency: 200
51-
print_stats: True
79+
score_to_win: 20000
80+
save_frequency: 50
81+
print_stats: True
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
params:
2+
seed: ${...seed}
3+
4+
algo:
5+
name: a2c_continuous
6+
7+
model:
8+
name: continuous_a2c_logstd
9+
10+
network:
11+
name: actor_critic
12+
separate: True
13+
14+
space:
15+
continuous:
16+
mu_activation: None
17+
sigma_activation: None
18+
mu_init:
19+
name: default
20+
sigma_init:
21+
name: const_initializer
22+
val: 0. # std = 1.
23+
fixed_sigma: True
24+
25+
mlp:
26+
units: [512] #, 256, 128]
27+
activation: elu
28+
d2rl: False
29+
30+
initializer:
31+
name: default
32+
regularizer:
33+
name: None
34+
rnn:
35+
name: lstm
36+
units: 256 #128
37+
layers: 1
38+
before_mlp: False #True
39+
concat_input: True
40+
layer_norm: False
41+
42+
43+
load_checkpoint: ${if:${...checkpoint},True,False} # flag which sets whether to load the checkpoint
44+
load_path: ${...checkpoint} # path to the checkpoint to load
45+
46+
config:
47+
name: ${resolve_default:AtlasTerrain,${....experiment}}
48+
full_experiment_name: ${.name}
49+
env_name: rlgpu
50+
ppo: True
51+
mixed_precision: True
52+
normalize_input: True
53+
normalize_value: True
54+
normalize_advantage: True
55+
value_bootstrap: True
56+
clip_actions: False
57+
num_actors: ${....task.env.numEnvs}
58+
reward_shaper:
59+
scale_value: 1.0
60+
gamma: 0.99
61+
tau: 0.95
62+
e_clip: 0.2
63+
entropy_coef: 0.001
64+
learning_rate: 3.e-4 # overwritten by adaptive lr_schedule
65+
lr_schedule: adaptive
66+
kl_threshold: 0.008 # target kl for adaptive lr
67+
truncate_grads: True
68+
grad_norm: 1.
69+
horizon_length: 24
70+
minibatch_size: 16
71+
mini_epochs: 5
72+
critic_coef: 2
73+
clip_value: True
74+
seq_len: 4 # only for rnn
75+
bounds_loss_coef: 0.
76+
77+
max_epochs: ${resolve_default:1000,${....max_iterations}}
78+
save_best_after: 200
79+
score_to_win: 20000
80+
save_frequency: 50
81+
print_stats: True

isaacgymenvs/tasks/__init__.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
from .anymal import Anymal
3232
from .anymal_terrain import AnymalTerrain
3333
from .atlas import Atlas
34+
from .atlas_terrain import AtlasTerrain
3435
from .ball_balance import BallBalance
3536
from .bittle import Bittle
3637
from .bittle_terrain import BittleTerrain
@@ -57,6 +58,7 @@
5758
"Anymal": Anymal,
5859
"AnymalTerrain": AnymalTerrain,
5960
"Atlas": Atlas,
61+
"AtlasTerrain": AtlasTerrain,
6062
"BallBalance": BallBalance,
6163
"Bittle": Bittle,
6264
"BittleTerrain": BittleTerrain,

0 commit comments

Comments
 (0)