Skip to content

Commit

Permalink
fix the setup
Browse files Browse the repository at this point in the history
  • Loading branch information
budzianowski committed Oct 1, 2024
1 parent 36618c8 commit 3375627
Show file tree
Hide file tree
Showing 3 changed files with 45 additions and 19 deletions.
2 changes: 1 addition & 1 deletion sim/envs/humanoids/stompypro_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ class rewards:
# put some settings here for LLM parameter tuning
target_joint_pos_scale = 0.17 # rad
target_feet_height = 0.05 # m
cycle_time = 0.4 # sec
cycle_time = 0.4 # sec # pfb30 - that should be longer and more stable
# if true negative total rewards are clipped at zero (avoids early termination problems)
only_positive_rewards = True
# tracking reward = exp(error*sigma)
Expand Down
45 changes: 33 additions & 12 deletions sim/resources/stompypro/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,16 @@ def stiffness(cls) -> Dict[str, float]:
"knee": 150,
"ankle_y": 75,
}

@classmethod
def stiffness_mujoco(cls) -> Dict[str, float]:
return {
"hip_y": 120,
"hip_x": 60,
"hip_z": 60,
"knee": 120,
"ankle_y": 17,
}

# d_gains
@classmethod
Expand All @@ -192,24 +202,35 @@ def damping(cls) -> Dict[str, float]:
"ankle_y": 5,
}

# pos_limits
@classmethod
def effort(cls) -> Dict[str, float]:
return {}

# vel_limits
@classmethod
def velocity(cls) -> Dict[str, float]:
def damping_mujoco(cls) -> Dict[str, float]:
return {
"hip": 5,
"hip_y": 5,
"hip_x": 5,
"hip_z": 5,
"knee": 5,
"ankle": 5,
"shoulder_y": 5,
"shoulder_z": 5,
"shoulder_x": 5,
"elbow_x": 5,
"ankle_y": 5,
}

# # pos_limits
# @classmethod
# def effort(cls) -> Dict[str, float]:
# return {}

# # vel_limits
# @classmethod
# def velocity(cls) -> Dict[str, float]:
# return {
# "hip": 5,
# "knee": 5,
# "ankle": 5,
# "shoulder_y": 5,
# "shoulder_z": 5,
# "shoulder_x": 5,
# "elbow_x": 5,
# }

@classmethod
def friction(cls) -> Dict[str, float]:
return {
Expand Down
17 changes: 11 additions & 6 deletions sim/sim2sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -151,8 +151,8 @@ def run_mujoco(policy, cfg):

cur_vel_obs = dq * cfg.normalization.obs_scales.dof_vel

obs[0, 0] = math.sin(2 * math.pi * count_lowlevel * cfg.sim_config.dt / 0.64)
obs[0, 1] = math.cos(2 * math.pi * count_lowlevel * cfg.sim_config.dt / 0.64)
obs[0, 0] = math.sin(2 * math.pi * count_lowlevel * cfg.sim_config.dt / 0.4)
obs[0, 1] = math.cos(2 * math.pi * count_lowlevel * cfg.sim_config.dt / 0.4)
obs[0, 2] = cmd.vx * cfg.normalization.obs_scales.lin_vel
obs[0, 3] = cmd.vy * cfg.normalization.obs_scales.lin_vel
obs[0, 4] = cmd.dyaw * cfg.normalization.obs_scales.ang_vel
Expand Down Expand Up @@ -184,6 +184,7 @@ def run_mujoco(policy, cfg):

tau = np.clip(tau, -cfg.robot_config.tau_limit, cfg.robot_config.tau_limit) # Clamp torques
print(tau)
# breakpoint()
data.ctrl = tau

mujoco.mj_step(model, data)
Expand Down Expand Up @@ -215,13 +216,17 @@ class env:

class sim_config:
sim_duration = 60.0
dt = 0.001
decimation = 20
dt = 0.002
decimation = 10

class rewards:
cycle_time = 0.4

class robot_config:
tau_factor = 0.85
tau_limit = np.array(list(robot.stiffness().values()) + list(robot.stiffness().values())) * tau_factor
kps = tau_limit
# pfb30 - bring back the original setup but fix the logic or call effort to have the same logic as in the script
tau_limit = np.array(list(robot.stiffness_mujoco().values()) + list(robot.stiffness_mujoco().values())) * tau_factor
kps = np.array(list(robot.stiffness().values()) + list(robot.stiffness().values()))
kds = np.array(list(robot.damping().values()) + list(robot.damping().values()))

class normalization:
Expand Down

0 comments on commit 3375627

Please sign in to comment.