Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
373 changes: 373 additions & 0 deletions assets/a1_license.txt

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions assets/meshes/calf.dae

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions assets/meshes/hip.dae

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions assets/meshes/thigh.dae

Large diffs are not rendered by default.

162 changes: 162 additions & 0 deletions assets/meshes/thigh_mirror.dae

Large diffs are not rendered by default.

188 changes: 188 additions & 0 deletions assets/meshes/trunk.dae

Large diffs are not rendered by default.

Binary file added assets/meshes/trunk_A1.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
578 changes: 578 additions & 0 deletions assets/urdf/a1.urdf

Large diffs are not rendered by default.

170 changes: 170 additions & 0 deletions isaacgymenvs/cfg/task/Quadruped.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,170 @@
# used to create the object
name: Quadruped

physics_engine: ${..physics_engine}

env:
numEnvs: ${resolve_default:4096,${...num_envs}}
envSpacing: 4. # [m]

clipObservations: 5.0
clipActions: 1.0

plane:
staticFriction: 1.0 # [-]
dynamicFriction: 1.0 # [-]
restitution: 0. # [-]

baseInitState:
pos: [0.0, 0.0, 0.62] # x,y,z [m]
rot: [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
vLinear: [0.0, 0.0, 0.0] # x,y,z [m/s]
vAngular: [0.0, 0.0, 0.0] # x,y,z [rad/s]

randomCommandVelocityRanges:
linear_x: [0., 2.] # min max [m/s]
linear_y: [0., 0.] # min max [m/s]
yaw: [-0., 0.] # min max [rad/s]

control:
# PD Drive parameters:
stiffness: 85.0 # [N*m/rad]
damping: 2.0 # [N*m*s/rad]
actionScale: 0.5
controlFrequencyInv: 1 # 60 Hz

defaultJointAngles: # = target angles when action = 0.0
FL_hip_joint: 0.03 # [rad]
RL_hip_joint: 0.03 # [rad]
FR_hip_joint: -0.03 # [rad]
RR_hip_joint: -0.03 # [rad]

FL_thigh_joint: 0.8 # [rad]
RL_thigh_joint: 0.8 # [rad]
FR_thigh_joint: 0.8 # [rad]
RR_thigh_joint: 0.8 # [rad]

FL_calf_joint: -1.6 # [rad]
RL_calf_joint: -1.6 # [rad]
FR_calf_joint: -1.6 # [rad]
RR_calf_joint: -1.6 # [rad]

urdfAsset:
collapseFixedJoints: True
fixBaseLink: False
defaultDofDriveMode: 4 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)

learn:
# rewards
linearVelocityXYRewardScale: 1.0
angularVelocityZRewardScale: 0.5
torqueRewardScale: -0.000025

# normalization
linearVelocityScale: 2.0
angularVelocityScale: 0.25
dofPositionScale: 1.0
dofVelocityScale: 0.05

# episode length in seconds
episodeLength_s: 50

# viewer cam:
viewer:
refEnv: 0
pos: [0, 0, 4] # [m]
lookat: [1., 1, 3.3] # [m]

# set to True if you use camera sensors in the environment
enableCameraSensors: False

sim:
dt: 0.02
substeps: 2
up_axis: "z"
use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
gravity: [0.0, 0.0, -9.81]
physx:
num_threads: ${....num_threads}
solver_type: ${....solver_type}
use_gpu: ${contains:"cuda",${....sim_device}} # set to False to run on CPU
num_position_iterations: 4
num_velocity_iterations: 1
contact_offset: 0.02
rest_offset: 0.0
bounce_threshold_velocity: 0.2
max_depenetration_velocity: 100.0
default_buffer_size_multiplier: 5.0
max_gpu_contact_pairs: 8388608 # 8*1024*1024
num_subscenes: ${....num_subscenes}
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!)

task:
randomize: False
randomization_params:
frequency: 600 # Define how many environment steps between generating new randomizations
observations:
range: [0, .002] # range for the white noise
operation: "additive"
distribution: "gaussian"
actions:
range: [0., .02]
operation: "additive"
distribution: "gaussian"
sim_params:
gravity:
range: [0, 0.4]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will linearly interpolate between no rand and max rand
schedule_steps: 3000
actor_params:
anymal:
color: True
rigid_body_properties:
mass:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
setup_only: True # Property will only be randomized once before simulation is started. See Domain Randomization Documentation for more info.
schedule: "linear" # "linear" will linearly interpolate between no rand and max rand
schedule_steps: 3000
rigid_shape_properties:
friction:
num_buckets: 500
range: [0.7, 1.3]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
restitution:
range: [0., 0.7]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
dof_properties:
damping:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
stiffness:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
lower:
range: [0, 0.01]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
upper:
range: [0, 0.01]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
179 changes: 179 additions & 0 deletions isaacgymenvs/cfg/task/QuadrupedAMP.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,179 @@
# used to create the object
name: QuadrupedAMP

physics_engine: ${..physics_engine}

env:
# AMP-specific things
motionFile: 'data/motions/quadruped/dog_mocap/dog_trot_hq.txt'
# End AMP-specific things
numEnvs: ${resolve_default:4096,${...num_envs}}
envSpacing: 4. # [m]
episodeLength_s: 8
cameraFollow: True # if the camera follows humanoid or not
enableDebugVis: False

pdControl: True
powerScale: 1.0
stateInit: "Random"
hybridInitProb: 0.5
numAMPObsSteps: 2

localRootObs: True
terminationHeight: 0.15
enableEarlyTermination: True

clipObservations: 5.0
clipActions: 1.0

plane:
staticFriction: 1.0 # [-]
dynamicFriction: 1.0 # [-]
restitution: 0. # [-]

baseInitState:
pos: [0.0, 0.0, 0.35] # x,y,z [m]
rot: [0.0, 0.0, 0.0, 1.0] # x,y,z,w [quat]
vLinear: [0.0, 0.0, 0.0] # x,y,z [m/s]
vAngular: [0.0, 0.0, 0.0] # x,y,z [rad/s]

randomCommandVelocityRanges:
linear_x: [0., 2.] # min max [m/s]
linear_y: [0., 0.] # min max [m/s]
yaw: [-0., 0.] # min max [rad/s]

control:
# PD Drive parameters:
stiffness: 40.0 # [N*m/rad]
damping: 1.0 # [N*m*s/rad]
# Replaced manual actionScale with automatic action scale calculated from URDF
# actionScale: 2.0
controlFrequencyInv: 1 # 60 Hz

defaultJointAngles: # = target angles when action = 0.0
FL_hip_joint: 0.0 # [rad]
RL_hip_joint: 0.0 # [rad]
FR_hip_joint: 0.0 # [rad]
RR_hip_joint: 0.0 # [rad]

FL_thigh_joint: 0.8 # [rad]
RL_thigh_joint: 0.8 # [rad]
FR_thigh_joint: 0.8 # [rad]
RR_thigh_joint: 0.8 # [rad]

FL_calf_joint: -1.6 # [rad]
RL_calf_joint: -1.6 # [rad]
FR_calf_joint: -1.6 # [rad]
RR_calf_joint: -1.6 # [rad]

urdfAsset:
collapseFixedJoints: True
fixBaseLink: False
defaultDofDriveMode: 4 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)

learn:
# normalization
linearVelocityScale: 2.0
angularVelocityScale: 0.25
dofPositionScale: 1.0
dofVelocityScale: 0.05

# viewer cam:
viewer:
refEnv: 0
pos: [0, 0, 4] # [m]
lookat: [1., 1, 3.3] # [m]

# set to True if you use camera sensors in the environment
enableCameraSensors: False

sim:
dt: 0.02
substeps: 2
up_axis: "z"
use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
gravity: [0.0, 0.0, -9.81]
physx:
num_threads: ${....num_threads}
solver_type: ${....solver_type}
use_gpu: ${contains:"cuda",${....sim_device}} # set to False to run on CPU
num_position_iterations: 4
num_velocity_iterations: 1
contact_offset: 0.02
rest_offset: 0.0
bounce_threshold_velocity: 0.2
max_depenetration_velocity: 100.0
default_buffer_size_multiplier: 5.0
max_gpu_contact_pairs: 8388608 # 8*1024*1024
num_subscenes: ${....num_subscenes}
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!)

task:
randomize: False
randomization_params:
frequency: 600 # Define how many environment steps between generating new randomizations
observations:
range: [0, .002] # range for the white noise
operation: "additive"
distribution: "gaussian"
actions:
range: [0., .02]
operation: "additive"
distribution: "gaussian"
sim_params:
gravity:
range: [0, 0.4]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will linearly interpolate between no rand and max rand
schedule_steps: 3000
actor_params:
anymal:
color: True
rigid_body_properties:
mass:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
setup_only: True # Property will only be randomized once before simulation is started. See Domain Randomization Documentation for more info.
schedule: "linear" # "linear" will linearly interpolate between no rand and max rand
schedule_steps: 3000
rigid_shape_properties:
friction:
num_buckets: 500
range: [0.7, 1.3]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
restitution:
range: [0., 0.7]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
dof_properties:
damping:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
stiffness:
range: [0.5, 1.5]
operation: "scaling"
distribution: "uniform"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
lower:
range: [0, 0.01]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
upper:
range: [0, 0.01]
operation: "additive"
distribution: "gaussian"
schedule: "linear" # "linear" will scale the current random sample by `min(current num steps, schedule_steps) / schedule_steps`
schedule_steps: 3000
Loading