|
| 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 |
0 commit comments