From 17de59ad94787289faec6c2d578764f7311bc82a Mon Sep 17 00:00:00 2001 From: craipy Date: Thu, 18 Jul 2024 09:45:05 +0800 Subject: [PATCH] add g1 task --- legged_gym/envs/__init__.py | 3 +- legged_gym/envs/g1/g1_config.py | 83 +++++++++++++++++++++++++++++++++ 2 files changed, 85 insertions(+), 1 deletion(-) create mode 100644 legged_gym/envs/g1/g1_config.py diff --git a/legged_gym/envs/__init__.py b/legged_gym/envs/__init__.py index f87d9b2..ea0a900 100644 --- a/legged_gym/envs/__init__.py +++ b/legged_gym/envs/__init__.py @@ -3,10 +3,11 @@ from legged_gym import LEGGED_GYM_ROOT_DIR, LEGGED_GYM_ENVS_DIR from legged_gym.envs.go2.go2_config import GO2RoughCfg, GO2RoughCfgPPO from legged_gym.envs.h1.h1_config import H1RoughCfg, H1RoughCfgPPO +from legged_gym.envs.g1.g1_config import G1RoughCfg, G1RoughCfgPPO from .base.legged_robot import LeggedRobot from legged_gym.utils.task_registry import task_registry task_registry.register( "go2", LeggedRobot, GO2RoughCfg(), GO2RoughCfgPPO()) task_registry.register( "h1", LeggedRobot, H1RoughCfg(), H1RoughCfgPPO()) - +task_registry.register( "g1", LeggedRobot, G1RoughCfg(), G1RoughCfgPPO()) diff --git a/legged_gym/envs/g1/g1_config.py b/legged_gym/envs/g1/g1_config.py new file mode 100644 index 0000000..e21f852 --- /dev/null +++ b/legged_gym/envs/g1/g1_config.py @@ -0,0 +1,83 @@ +from legged_gym.envs.base.legged_robot_config import LeggedRobotCfg, LeggedRobotCfgPPO + +class G1RoughCfg( LeggedRobotCfg ): + class init_state( LeggedRobotCfg.init_state ): + pos = [0.0, 0.0, 0.8] # x,y,z [m] + default_joint_angles = { # = target angles [rad] when action = 0.0 + 'left_hip_yaw_joint' : 0. , + 'left_hip_roll_joint' : 0, + 'left_hip_pitch_joint' : -0.1, + 'left_knee_joint' : 0.3, + 'left_ankle_pitch_joint' : -0.2, + 'left_ankle_roll_joint' : 0, + 'right_hip_yaw_joint' : 0., + 'right_hip_roll_joint' : 0, + 'right_hip_pitch_joint' : -0.1, + 'right_knee_joint' : 0.3, + 'right_ankle_pitch_joint': -0.2, + 'right_ankle_roll_joint' : 0, + 'torso_joint' : 0. + } + + class env(LeggedRobotCfg.env): + num_observations = 48 + num_actions = 12 + + + class control( LeggedRobotCfg.control ): + # PD Drive parameters: + control_type = 'P' + # PD Drive parameters: + stiffness = {'hip_yaw': 150, + 'hip_roll': 150, + 'hip_pitch': 150, + 'knee': 300, + 'ankle': 40, + } # [N*m/rad] + damping = { 'hip_yaw': 2, + 'hip_roll': 2, + 'hip_pitch': 2, + 'knee': 4, + 'ankle': 2, + } # [N*m/rad] # [N*m*s/rad] + # action scale: target angle = actionScale * action + defaultAngle + action_scale = 0.25 + # decimation: Number of control action updates @ sim DT per policy DT + decimation = 4 + + class asset( LeggedRobotCfg.asset ): + file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/g1/urdf/g1.urdf' + name = "g1" + foot_name = "ankle_roll" + penalize_contacts_on = ["hip", "knee"] + terminate_after_contacts_on = ["torso"] + self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter + flip_visual_attachments = False + + class rewards( LeggedRobotCfg.rewards ): + soft_dof_pos_limit = 0.9 + base_height_target = 0.728 + class scales( LeggedRobotCfg.rewards.scales ): + tracking_lin_vel = 1.0 + tracking_ang_vel = 0.5 + lin_vel_z = -2.0 + ang_vel_xy = -0.05 + orientation = -1.0 + base_height = -10.0 + dof_acc = -2.5e-8 + feet_air_time = 1.0 + collision = 0.0 + action_rate = -0.01 + # torques = -0.0001 + dof_pos_limits = -5.0 + +class G1RoughCfgPPO( LeggedRobotCfgPPO ): + class policy: + init_noise_std = 0.8 + class algorithm( LeggedRobotCfgPPO.algorithm ): + entropy_coef = 0.01 + class runner( LeggedRobotCfgPPO.runner ): + run_name = '' + experiment_name = 'g1' + +