From fa8be99c1f883cf166744e59e8cad6436b918cde Mon Sep 17 00:00:00 2001 From: is2ac2 Date: Thu, 18 Jul 2024 14:28:51 -0700 Subject: [PATCH] current version --- sim/deploy/policy.py | 2 +- sim/deploy/run.py | 16 ++++--- sim/humanoid_gym/envs/only_legs_config.py | 43 ++++++++--------- sim/stompy_legs/joints.py | 46 +++++++++--------- sim/stompy_legs/robot_fixed.xml | 58 ++++++++++++----------- 5 files changed, 84 insertions(+), 81 deletions(-) diff --git a/sim/deploy/policy.py b/sim/deploy/policy.py index 41500c23..938a41c5 100755 --- a/sim/deploy/policy.py +++ b/sim/deploy/policy.py @@ -112,7 +112,7 @@ def pd_control( # breakpoint() res = ( (target_dof_pos - dof_pos) * kp + (target_dof_vel - dof_vel) * kd ) # breakpoint() - return res * 0.75 + return res * 0.0025 def parse_action( self, dof_pos: np.ndarray, dof_vel: np.ndarray, eu_ang: np.ndarray, ang_vel: np.ndarray, count_lowlevel: int diff --git a/sim/deploy/run.py b/sim/deploy/run.py index f4e4aa22..18bdb4f6 100755 --- a/sim/deploy/run.py +++ b/sim/deploy/run.py @@ -88,7 +88,7 @@ def step( dq: The current joint velocities. target_dq: The target joint velocities (optional). """ - # tau = np.clip(tau, -self.cfg.tau_limit, self.cfg.tau_limit) + tau = np.clip(tau, -self.cfg.tau_limit, self.cfg.tau_limit) self.data.ctrl = tau mujoco.mj_step(self.model, self.data) @@ -136,6 +136,8 @@ def simulate(self, policy: SimPolicy) -> None: # target_dof_pos = np.zeros_like(target_dof_pos) tau = policy.pd_control(target_dof_pos, dof_pos, cfg.kps, dof_vel, cfg.kds) # breakpoint() + if step % 1000 == 0: + breakpoint() # set tau to zero for now # tau = np.zeros_like(tau) self.step(tau=tau) @@ -273,12 +275,12 @@ def main(args: argparse.Namespace, cfg: RobotConfig) -> None: num_single_obs = dof * 3 + 11 # is2ac, lets scale kps and kds to be the same as our stiffness and dmaping - kps = np.ones((dof), dtype=np.double) * 0.00001 * 25 - kds = np.ones((dof), dtype=np.double) * 1 - tau_limit = np.ones((dof), dtype=np.double) * 0.00001 * 25 - # kps = np.ones((dof), dtype=np.double) * 200 - # kds = np.ones((dof), dtype=np.double) * 10 - # tau_limit = np.ones((dof), dtype=np.double) * 200 + # kps = np.ones((dof), dtype=np.double) + # kds = np.ones((dof), dtype=np.double) * 1 + # tau_limit = np.ones((dof), dtype=np.double) + kps = np.ones((dof), dtype=np.double) * 200 + kds = np.ones((dof), dtype=np.double) * 10 + tau_limit = np.ones((dof), dtype=np.double) * 200 cfg = RobotConfig( robot_model_path=robot_path, dof=dof, kps=kps, kds=kds, tau_limit=tau_limit, num_single_obs=num_single_obs diff --git a/sim/humanoid_gym/envs/only_legs_config.py b/sim/humanoid_gym/envs/only_legs_config.py index 70a46b3a..9ebf5ce9 100755 --- a/sim/humanoid_gym/envs/only_legs_config.py +++ b/sim/humanoid_gym/envs/only_legs_config.py @@ -117,10 +117,10 @@ class control(LeggedRobotCfg.control): "ankle": 10, "knee": 10, } - for k in stiffness: - stiffness[k] *= 0.00001 - damping[k] *= 0.1 - action_scale = 2500 + # for k in stiffness: + # stiffness[k] *= 0.00001 + # damping[k] *= 0.1 + action_scale = 0.25 # decimation: Number of control action updates @ sim DT per policy DT decimation = 10 # 100hz @@ -135,7 +135,7 @@ class physx(LeggedRobotCfg.sim.physx): num_position_iterations = 4 num_velocity_iterations = 1 contact_offset = 0.01 # [m] - rest_offset = 0.0 # -0.02 # [m] + rest_offset = 0 # -0.02 # [m] bounce_threshold_velocity = 0.1 # [m/s] max_depenetration_velocity = 1.0 max_gpu_contact_pairs = 2**23 # 2**24 -> needed for 8000 envs and more @@ -190,22 +190,22 @@ class rewards: class scales: # reference motion tracking - # joint_pos = 1.6 - # feet_clearance = 1.0 - # feet_contact_number = 1.2 - # # gait - # feet_air_time = 1.0 - # foot_slip = -0.05 - # feet_distance = 0.2 - # knee_distance = 0.2 - # # contact - # feet_contact_forces = -0.01 - # # vel tracking - # tracking_lin_vel = 1.2 - # tracking_ang_vel = 1.1 - # vel_mismatch_exp = 0.5 # lin_z; ang x,y - # low_speed = 0.2 - # track_vel_hard = 0.5 + joint_pos = 1.6 + feet_clearance = 1.0 + feet_contact_number = 1.2 + # gait + feet_air_time = 1.0 + foot_slip = -0.05 + feet_distance = 0.2 + knee_distance = 0.2 + # contact + feet_contact_forces = -0.01 + # vel tracking + tracking_lin_vel = 1.2 + tracking_ang_vel = 1.1 + vel_mismatch_exp = 0.5 # lin_z; ang x,y + low_speed = 0.2 + track_vel_hard = 0.5 # above this was removed for standing policy # base pos @@ -223,7 +223,6 @@ class scales: class normalization: class obs_scales: - # is2ac lin_vel = 2.0 ang_vel = 1.0 dof_pos = 1.0 diff --git a/sim/stompy_legs/joints.py b/sim/stompy_legs/joints.py index 4c3f0007..4e4be441 100755 --- a/sim/stompy_legs/joints.py +++ b/sim/stompy_legs/joints.py @@ -86,31 +86,31 @@ def default_positions(cls) -> Dict[str, float]: def default_standing(cls) -> Dict[str, float]: return { # legs - Stompy.legs.right.hip_pitch: 0, - Stompy.legs.right.hip_yaw: -2.15, - Stompy.legs.right.hip_roll: -1.6, - Stompy.legs.right.knee_pitch: 2.16, - Stompy.legs.right.ankle_pitch: 0.5, - Stompy.legs.right.ankle_roll: 1.72, - Stompy.legs.left.hip_pitch: 1.61, - Stompy.legs.left.hip_yaw: 1, - Stompy.legs.left.hip_roll: 0, - Stompy.legs.left.knee_pitch: 2.05, - Stompy.legs.left.ankle_pitch: 0.33, - Stompy.legs.left.ankle_roll: 1.73, - # legs in squat - # Stompy.legs.left.hip_pitch: 1.17, - # Stompy.legs.left.hip_roll: 0.1, - # Stompy.legs.left.hip_yaw: 1.03, - # Stompy.legs.left.knee_pitch: 1.13, - # Stompy.legs.left.ankle_pitch: -0.27, - # Stompy.legs.left.ankle_roll: 1.73, - # Stompy.legs.right.hip_pitch: 0.38, - # Stompy.legs.right.hip_roll: -1.6, + # Stompy.legs.right.hip_pitch: 0, # Stompy.legs.right.hip_yaw: -2.15, - # Stompy.legs.right.knee_pitch: 2.94, - # Stompy.legs.right.ankle_pitch: 0.8, + # Stompy.legs.right.hip_roll: -1.6, + # Stompy.legs.right.knee_pitch: 2.16, + # Stompy.legs.right.ankle_pitch: 0.5, # Stompy.legs.right.ankle_roll: 1.72, + # Stompy.legs.left.hip_pitch: 1.61, + # Stompy.legs.left.hip_yaw: 1, + # Stompy.legs.left.hip_roll: 0, + # Stompy.legs.left.knee_pitch: 2.05, + # Stompy.legs.left.ankle_pitch: 0.33, + # Stompy.legs.left.ankle_roll: 1.73, + # legs in squat + Stompy.legs.left.hip_pitch: 1.17, + Stompy.legs.left.hip_roll: 0.1, + Stompy.legs.left.hip_yaw: 1.03, + Stompy.legs.left.knee_pitch: 1.13, + Stompy.legs.left.ankle_pitch: -0.27, + Stompy.legs.left.ankle_roll: 1.73, + Stompy.legs.right.hip_pitch: 0.38, + Stompy.legs.right.hip_roll: -1.6, + Stompy.legs.right.hip_yaw: -2.15, + Stompy.legs.right.knee_pitch: 2.94, + Stompy.legs.right.ankle_pitch: 0.8, + Stompy.legs.right.ankle_roll: 1.72, } @classmethod diff --git a/sim/stompy_legs/robot_fixed.xml b/sim/stompy_legs/robot_fixed.xml index 5948e954..bb889a10 100644 --- a/sim/stompy_legs/robot_fixed.xml +++ b/sim/stompy_legs/robot_fixed.xml @@ -1,22 +1,24 @@ - + - + + + - - - - + - + \ No newline at end of file