From d537864b4df19a2cfc762b02116ad09e52e8048e Mon Sep 17 00:00:00 2001 From: Wesley Maa Date: Thu, 2 Jan 2025 01:03:34 -0800 Subject: [PATCH 1/5] lint --- sim/envs/base/legged_robot.py | 1 - sim/envs/humanoids/gpr_config.py | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/sim/envs/base/legged_robot.py b/sim/envs/base/legged_robot.py index 1cc6e5af..1b17e60b 100644 --- a/sim/envs/base/legged_robot.py +++ b/sim/envs/base/legged_robot.py @@ -471,7 +471,6 @@ def update_command_curriculum(self, env_ids): self.command_ranges["lin_vel_x"][1] + 0.5, 0.0, self.cfg.commands.max_curriculum ) - def _resample_default_positions(self): self.default_dof_pos = torch.zeros(self.num_dof, dtype=torch.float, device=self.device, requires_grad=False) for i in range(self.num_dofs): diff --git a/sim/envs/humanoids/gpr_config.py b/sim/envs/humanoids/gpr_config.py index 9bd940d2..8099328d 100644 --- a/sim/envs/humanoids/gpr_config.py +++ b/sim/envs/humanoids/gpr_config.py @@ -169,7 +169,7 @@ class noise_scales: height_measurements = 0.1 class noise_ranges: - default_pos = 0.03 # +- 0.05 rad + default_pos = 0.03 # +- 0.05 rad class init_state(LeggedRobotCfg.init_state): pos = [0.0, 0.0, Robot.height] From 20add09d3eedd02aefbce6a8feb99f9e761d51f2 Mon Sep 17 00:00:00 2001 From: Wesley Maa Date: Thu, 2 Jan 2025 14:54:21 -0800 Subject: [PATCH 2/5] get name from schema --- sim/sim2sim.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/sim/sim2sim.py b/sim/sim2sim.py index 3823d8c0..c737521b 100755 --- a/sim/sim2sim.py +++ b/sim/sim2sim.py @@ -392,6 +392,12 @@ def run_mujoco( policy = ONNXModel(args.load_model) metadata = policy.attached_metadata + joint_names = [] + for value_schema in policy.input_schema.values + policy.output_schema.values: + if value_schema.HasField("joint_positions"): + joint_names = list(value_schema.joint_positions.joint_names) + break + try: model_info = { "num_actions": metadata["num_actions"], @@ -402,7 +408,7 @@ def run_mujoco( "sim_dt": metadata["sim_dt"], "sim_decimation": metadata["sim_decimation"], "tau_factor": metadata["tau_factor"], - "joint_names": metadata["joint_names"], + "joint_names": joint_names, "cycle_time": metadata["cycle_time"], } except Exception as e: From 07b9a9dde9835354dedef98a9af615109baed109 Mon Sep 17 00:00:00 2001 From: Wesley Maa Date: Thu, 2 Jan 2025 14:57:00 -0800 Subject: [PATCH 3/5] fix --- sim/envs/humanoids/gpr_config.py | 4 ++-- sim/sim2sim.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/sim/envs/humanoids/gpr_config.py b/sim/envs/humanoids/gpr_config.py index 8099328d..506591b6 100644 --- a/sim/envs/humanoids/gpr_config.py +++ b/sim/envs/humanoids/gpr_config.py @@ -6,6 +6,8 @@ LeggedRobotCfgPPO, ) from sim.resources.gpr.joints import Robot +from kinfer import proto as P + NUM_JOINTS = len(Robot.all_joints()) @@ -26,8 +28,6 @@ class env(LeggedRobotCfg.env): episode_length_s = 24 # episode length in seconds use_ref_actions = False - from kinfer import proto as P - input_schema = P.IOSchema( values=[ P.ValueSchema( diff --git a/sim/sim2sim.py b/sim/sim2sim.py index c737521b..a32515e5 100755 --- a/sim/sim2sim.py +++ b/sim/sim2sim.py @@ -393,7 +393,7 @@ def run_mujoco( metadata = policy.attached_metadata joint_names = [] - for value_schema in policy.input_schema.values + policy.output_schema.values: + for value_schema in policy.input_schema.values: if value_schema.HasField("joint_positions"): joint_names = list(value_schema.joint_positions.joint_names) break From d37961d14569bf5d893fcbf9bddb6a88f41d2638 Mon Sep 17 00:00:00 2001 From: Wesley Maa Date: Thu, 2 Jan 2025 14:58:01 -0800 Subject: [PATCH 4/5] lint --- sim/envs/humanoids/gpr_config.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sim/envs/humanoids/gpr_config.py b/sim/envs/humanoids/gpr_config.py index 506591b6..56ceaebc 100644 --- a/sim/envs/humanoids/gpr_config.py +++ b/sim/envs/humanoids/gpr_config.py @@ -1,13 +1,13 @@ """Defines the environment configuration for the Getting up task""" +from kinfer import proto as P + from sim.env import robot_urdf_path from sim.envs.base.legged_robot_config import ( # type: ignore LeggedRobotCfg, LeggedRobotCfgPPO, ) from sim.resources.gpr.joints import Robot -from kinfer import proto as P - NUM_JOINTS = len(Robot.all_joints()) From 34783c0ecc036beae52dc659c4cb57c7c30923d1 Mon Sep 17 00:00:00 2001 From: Wesley Maa Date: Thu, 2 Jan 2025 14:59:30 -0800 Subject: [PATCH 5/5] more info from schema --- sim/sim2sim.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sim/sim2sim.py b/sim/sim2sim.py index a32515e5..8b846ce9 100755 --- a/sim/sim2sim.py +++ b/sim/sim2sim.py @@ -400,11 +400,11 @@ def run_mujoco( try: model_info = { - "num_actions": metadata["num_actions"], + "num_actions": len(joint_names), "num_observations": metadata["num_observations"], - "robot_effort": [metadata["robot_effort"][joint] for joint in metadata["joint_names"]], - "robot_stiffness": [metadata["robot_stiffness"][joint] for joint in metadata["joint_names"]], - "robot_damping": [metadata["robot_damping"][joint] for joint in metadata["joint_names"]], + "robot_effort": [metadata["robot_effort"][joint] for joint in joint_names], + "robot_stiffness": [metadata["robot_stiffness"][joint] for joint in joint_names], + "robot_damping": [metadata["robot_damping"][joint] for joint in joint_names], "sim_dt": metadata["sim_dt"], "sim_decimation": metadata["sim_decimation"], "tau_factor": metadata["tau_factor"],