# used to create the object
name: AnymalTerrain

physics_engine: 'physx'

env:
  numEnvs: ${resolve_default:256,${...num_envs}}
  numObservations: 36
  numActions: 12
  envSpacing: 3.  # [m]
  enableDebugVis: False

  terrain:
    terrainType: trimesh # none, plane, or trimesh
    staticFriction: 1.0  # [-]
    dynamicFriction: 1.0  # [-]
    restitution: 0.        # [-]
    # rough terrain only:
    curriculum: true
    maxInitMapLevel: 0
    mapLength: 6.
    mapWidth: 6.
    numLevels: 4
    numTerrains: 4
    # terrain types: [smooth slope, rough slope, stairs up, stairs down, discrete]
    terrainProportions: [0.1, 0.1, 0.35, 0.25, 0.2]
    # tri mesh only:
    slopeTreshold: 0.5

  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:
    # train
    linear_x: [-1., 1.] # min max [m/s]
    linear_y: [-1., 1.]   # min max [m/s]
    yaw: [-3.14, 3.14]    # min max [rad/s]

  control:
    # PD Drive parameters:
    stiffness: 80.0  # [N*m/rad]
    damping: 2.0     # [N*m*s/rad]
    # action scale: target angle = actionScale * action + defaultAngle
    actionScale: 0.5
    # decimation: Number of control action updates @ sim DT per policy DT
    decimation: 4

  defaultJointAngles:  # = target angles when action = 0.0
    LF_HAA: 0.03    # [rad]
    LH_HAA: 0.03    # [rad]
    RF_HAA: -0.03   # [rad]
    RH_HAA: -0.03   # [rad]

    LF_HFE: 0.4     # [rad]
    LH_HFE: -0.4    # [rad]
    RF_HFE: 0.4     # [rad]
    RH_HFE: -0.4    # [rad]

    LF_KFE: -0.8    # [rad]
    LH_KFE: 0.8     # [rad]
    RF_KFE: -0.8    # [rad]
    RH_KFE: 0.8     # [rad]

  urdfAsset:
    file: "urdf/anymal_c/urdf/anymal_minimal.urdf"
    footName: SHANK # SHANK if collapsing fixed joint, FOOT otherwise
    kneeName: THIGH
    collapseFixedJoints: false #True
    fixBaseLink: false
    defaultDofDriveMode: 4 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 4 effort)

  learn:
    allowKneeContacts: false #true
    # rewards
    terminalReward: 0.0
    linearVelocityXYRewardScale: 1.0
    linearVelocityZRewardScale: -4.0 #-4.0
    angularVelocityXYRewardScale: -0.5 #-0.5
    angularVelocityZRewardScale: 0.5
    orientationRewardScale: -0. #-1.
    torqueRewardScale: -0.00002 # -0.000025
    jointAccRewardScale: -0.0005 # -0.0025
    baseHeightRewardScale: -0.0 #5
    feetAirTimeRewardScale:  0.0 #1.0
    kneeCollisionRewardScale: -0.25 
    feetStumbleRewardScale: -2.0 #-2.0
    actionRateRewardScale: -0.01
    # cosmetics
    hipRewardScale: 0.0 #25

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

    # noise 
    addNoise: false
    noiseLevel: 1.0 # scales other values
    dofPositionNoise: 0.01
    dofVelocityNoise: 1.5
    linearVelocityNoise: 0.1
    angularVelocityNoise: 0.2
    gravityNoise: 0.05
    heightMeasurementNoise: 0.06

    #randomization
    randomizeFriction: true
    frictionRange: [0.5, 1.25]
    pushRobots: true
    pushInterval_s: 15

    # episode length in seconds
    episodeLength_s: 20

  # viewer cam:
  viewer:
    refEnv: 0
    pos: [0, 0, 10]  # [m]
    lookat: [1., 1, 9]  # [m]

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

sim:
  dt: 0.005
  substeps: 1
  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 (default - all contacts)

task:
  randomize: False
