Skip to content

Commit

Permalink
deprecate env_spacing, because plane has a limited size
Browse files Browse the repository at this point in the history
  • Loading branch information
lupinjia committed Feb 10, 2025
1 parent 362df97 commit e94760d
Show file tree
Hide file tree
Showing 7 changed files with 67 additions and 51 deletions.
5 changes: 3 additions & 2 deletions legged_gym/envs/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
from legged_gym import LEGGED_GYM_ROOT_DIR, LEGGED_GYM_ENVS_DIR
from .base.legged_robot import LeggedRobot
# go2
from legged_gym.envs.go2.go2 import GO2
from legged_gym.envs.go2.go2_config import GO2Cfg, GO2CfgPPO
# go2_rough
from legged_gym.envs.go2.go2_rough.go2_rough_config import GO2RoughCfg, GO2RoughCfgPPO
Expand All @@ -43,7 +44,7 @@

from legged_gym.utils.task_registry import task_registry

task_registry.register( "go2", LeggedRobot, GO2Cfg(), GO2CfgPPO())
task_registry.register( "go2_rough", LeggedRobot, GO2RoughCfg(), GO2RoughCfgPPO())
task_registry.register( "go2", GO2, GO2Cfg(), GO2CfgPPO())
task_registry.register( "go2_rough", GO2, GO2RoughCfg(), GO2RoughCfgPPO())
task_registry.register( "go2_deploy", GO2Deploy, GO2DeployCfg(), GO2DeployCfgPPO())
task_registry.register( "bipedal_walker", BipedalWalker, BipedalWalkerCfg(), BipedalWalkerCfgPPO())
41 changes: 26 additions & 15 deletions legged_gym/envs/base/legged_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,12 @@ def step(self, actions):
clip_actions = self.cfg.normalization.clip_actions
self.actions = torch.clip(actions, -clip_actions, clip_actions).to(self.device)
exec_actions = self.last_actions if self.simulate_action_latency else self.actions
if self.cfg.sim.use_implicit_controller:
if self.cfg.sim.use_implicit_controller: # use embedded pd controller
target_dof_pos = self._compute_target_dof_pos(exec_actions)
self.robot.control_dofs_position(target_dof_pos, self.motor_dofs)
self.scene.step()
else:
for _ in range(self.cfg.control.decimation):
for _ in range(self.cfg.control.decimation): # use self-implemented pd controller
self.torques = self._compute_torques(exec_actions)
if self.num_build_envs == 0:
torques = self.torques.squeeze()
Expand Down Expand Up @@ -102,8 +102,7 @@ def post_physics_step(self):
self._post_physics_step_callback()

# compute observations, rewards, resets, ...
if self.cfg.terrain.mesh_type == "heightfield":
self.check_base_pos_out_of_bound()
self.check_base_pos_out_of_bound()
self.check_termination()
self.compute_reward()
env_ids = self.reset_buf.nonzero(as_tuple=False).flatten()
Expand Down Expand Up @@ -258,7 +257,7 @@ def create_sim(self):
camera_lookat=(0.0, 0.0, 0.5),
camera_fov=40,
),
vis_options=gs.options.VisOptions(n_rendered_envs=self.cfg.viewer.num_rendered_envs),
vis_options=gs.options.VisOptions(n_rendered_envs=min(self.cfg.viewer.num_rendered_envs, self.num_envs)),
rigid_options=gs.options.RigidOptions(
dt=self.sim_dt,
constraint_solver=gs.constraint_solver.Newton,
Expand All @@ -279,7 +278,7 @@ def create_sim(self):
self._setup_camera()

# add terrain
mesh_type = self.cfg.terrain.mesh_type # only plane for now
mesh_type = self.cfg.terrain.mesh_type
if mesh_type=='plane':
self.terrain = self.scene.add_entity(gs.morphs.URDF(file="urdf/plane/plane.urdf", fixed=True))
elif mesh_type=='heightfield':
Expand All @@ -288,6 +287,20 @@ def create_sim(self):
elif mesh_type is not None:
raise ValueError("Terrain mesh type not recognised. Allowed types are [None, plane, heightfield, trimesh]")
self.terrain.set_friction(self.cfg.terrain.friction)
# specify the boundary of the heightfield
self.terrain_x_range = torch.zeros(2, device=self.device)
self.terrain_y_range = torch.zeros(2, device=self.device)
if self.cfg.terrain.mesh_type=='heightfield':
self.terrain_x_range[0] = -self.cfg.terrain.border_size + 1.0 # give a small margin(1.0m)
self.terrain_x_range[1] = self.cfg.terrain.border_size + self.cfg.terrain.num_rows * self.cfg.terrain.terrain_length - 1.0
self.terrain_y_range[0] = -self.cfg.terrain.border_size + 1.0
self.terrain_y_range[1] = self.cfg.terrain.border_size + self.cfg.terrain.num_cols * self.cfg.terrain.terrain_width - 1.0
elif self.cfg.terrain.mesh_type=='plane': # the plane used has limited size,
# and the origin of the world is at the center of the plane
self.terrain_x_range[0] = -self.cfg.terrain.plane_length/2+1
self.terrain_x_range[1] = self.cfg.terrain.plane_length/2-1
self.terrain_y_range[0] = -self.cfg.terrain.plane_length/2+1 # the plane is a square
self.terrain_y_range[1] = self.cfg.terrain.plane_length/2-1
self._create_envs()

def set_camera(self, pos, lookat):
Expand Down Expand Up @@ -607,13 +620,6 @@ def _create_heightfield(self):
)
self.height_samples = torch.tensor(self.utils_terrain.heightsamples).view(
self.utils_terrain.tot_rows, self.utils_terrain.tot_cols).to(self.device)
# specify the boundary of the heightfield
self.terrain_x_range = torch.zeros(2, device=self.device)
self.terrain_y_range = torch.zeros(2, device=self.device)
self.terrain_x_range[0] = -self.cfg.terrain.border_size + 1.0 # give a small margin(1.0m)
self.terrain_x_range[1] = self.cfg.terrain.border_size + self.cfg.terrain.num_rows * self.cfg.terrain.terrain_length - 1.0
self.terrain_y_range[0] = -self.cfg.terrain.border_size + 1.0
self.terrain_y_range[1] = self.cfg.terrain.border_size + self.cfg.terrain.num_cols * self.cfg.terrain.terrain_width - 1.0

def _create_envs(self):
""" Creates environments:
Expand Down Expand Up @@ -778,10 +784,14 @@ def _get_env_origins(self):
num_cols = np.floor(np.sqrt(self.num_envs))
num_rows = np.ceil(self.num_envs / num_cols)
xx, yy = torch.meshgrid(torch.arange(num_rows), torch.arange(num_cols))
spacing = self.cfg.env.env_spacing
# plane has limited size, we need to specify spacing base on num_envs, to make sure all robots are within the plane
# restrict envs to a square of [plane_length/2, plane_length/2]
spacing = min((self.cfg.terrain.plane_length / 2) / (num_rows-1), (self.cfg.terrain.plane_length / 2) / (num_cols-1))
self.env_origins[:, 0] = spacing * xx.flatten()[:self.num_envs]
self.env_origins[:, 1] = spacing * yy.flatten()[:self.num_envs]
self.env_origins[:, 2] = 0.
self.env_origins[:, 0] -= self.cfg.terrain.plane_length / 4
self.env_origins[:, 1] -= self.cfg.terrain.plane_length / 4

def _init_height_points(self):
""" Returns points at which the height measurments are sampled (in base frame)
Expand Down Expand Up @@ -853,7 +863,8 @@ def _reward_orientation(self):
def _reward_base_height(self):
# Penalize base height away from target
base_height = torch.mean(self.base_pos[:, 2].unsqueeze(1) - self.measured_heights, dim=1)
return torch.square(base_height - self.cfg.rewards.base_height_target)
rew = torch.square(base_height - self.cfg.rewards.base_height_target)
return rew

def _reward_torques(self):
# Penalize torques
Expand Down
4 changes: 2 additions & 2 deletions legged_gym/envs/base/legged_robot_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,14 @@ class env:
num_observations = 48
num_privileged_obs = None # if not None a priviledge_obs_buf will be returned by step() (critic obs for assymetric training). None is returned otherwise
num_actions = 12
env_spacing = 3. # not used with heightfields/trimeshes
send_timeouts = True # send time out information to the algorithm
episode_length_s = 20 # episode length in seconds
debug = False # if debugging, visualize contacts,
debug_viz = False # draw debug visualizations

class terrain:
mesh_type = 'plane' # "heightfield" # none, plane, heightfield or trimesh
mesh_type = 'plane' # "heightfield" # none, plane, heightfield
plane_length = 200.0 # [m]. plane size is 200x200x10 by default
horizontal_scale = 0.1 # [m]
vertical_scale = 0.005 # [m]
border_size = 5 # [m]
Expand Down
22 changes: 0 additions & 22 deletions legged_gym/envs/go2/go2.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,28 +18,6 @@
from .go2_config import GO2Cfg

class GO2(LeggedRobot):
def __init__(self, cfg: GO2Cfg, sim_device, headless):
""" Parses the provided config file,
calls create_sim() (which creates, simulation, terrain and environments),
initilizes pytorch buffers used during training
Args:
cfg (Dict): Environment config file
device_type (string): 'cuda' or 'cpu'
device_id (int): 0, 1, ...
headless (bool): Run without rendering if True
"""
self.cfg = cfg
self.height_samples = None
self.debug_viz = self.cfg.env.debug_viz
self.init_done = False
self._parse_cfg(self.cfg)
super().__init__(self.cfg, sim_device, headless)

self._init_buffers()
self._prepare_reward_function()
self.init_done = True

def _reset_dofs(self, envs_idx):
""" Resets DOF position and velocities of selected environmments
Positions are randomly selected within 0.5:1.5 x default positions.
Expand Down
7 changes: 3 additions & 4 deletions legged_gym/envs/go2/go2_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@ class env( LeggedRobotCfg.env ):
num_envs = 10000
num_observations = 48
num_actions = 12
env_spacing = 3. # not used with heightfields/trimeshes

class terrain( LeggedRobotCfg.terrain ):
mesh_type = "plane" # none, plane, heightfield
Expand Down Expand Up @@ -85,7 +84,7 @@ class scales( LeggedRobotCfg.rewards.scales ):
torques = -2.e-4
# gait
feet_air_time = 1.0
dof_close_to_default = -0.1
# dof_close_to_default = -0.1

class commands( LeggedRobotCfg.commands ):
curriculum = True
Expand Down Expand Up @@ -116,7 +115,7 @@ class viewer:
ref_env = 0
pos = [10, 0, 6] # [m]
lookat = [11., 5, 3.] # [m]
num_rendered_envs = 100 # number of environments to be rendered
num_rendered_envs = 10 # number of environments to be rendered
add_camera = False

class GO2CfgPPO( LeggedRobotCfgPPO ):
Expand All @@ -126,6 +125,6 @@ class runner( LeggedRobotCfgPPO.runner ):
run_name = ''
experiment_name = 'go2'
save_interval = 100
load_run = "Dec22_13-55-49_"
load_run = "Feb10_21-29-29_"
checkpoint = -1
max_iterations = 600
11 changes: 5 additions & 6 deletions legged_gym/scripts/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ def play(args):
env_cfg.env.num_envs = min(env_cfg.env.num_envs, 10)
env_cfg.env.debug_viz = True
env_cfg.viewer.add_camera = True # use a extra camera for moving
env_cfg.viewer.num_rendered_envs = 10
env_cfg.terrain.border_size = 5
env_cfg.terrain.num_rows = 2
env_cfg.terrain.num_cols = 5
Expand All @@ -33,10 +32,10 @@ def play(args):
# initial state randomization
env_cfg.init_state.yaw_angle_range = [0., 0.]
# velocity range
# env_cfg.commands.ranges.lin_vel_x = [0.5, 1.0]
# env_cfg.commands.ranges.lin_vel_y = [0., 0.]
# env_cfg.commands.ranges.ang_vel_yaw = [0., 0.]
# env_cfg.commands.ranges.heading = [0, 0]
env_cfg.commands.ranges.lin_vel_x = [0.5, 1.0]
env_cfg.commands.ranges.lin_vel_y = [0., 0.]
env_cfg.commands.ranges.ang_vel_yaw = [0., 0.]
env_cfg.commands.ranges.heading = [0, 0]

# prepare environment
env, _ = task_registry.make_env(name=args.task, args=args, env_cfg=env_cfg)
Expand Down Expand Up @@ -122,7 +121,7 @@ def play(args):

if __name__ == '__main__':
EXPORT_POLICY = False
RECORD_FRAMES = True # only record frames in extra camera view
RECORD_FRAMES = False # only record frames in extra camera view
MOVE_CAMERA = False
FOLLOW_ROBOT = True
assert not (MOVE_CAMERA and FOLLOW_ROBOT), "Cannot move camera and follow robot at the same time"
Expand Down
28 changes: 28 additions & 0 deletions resources/plane/plane.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="0.0" ?>
<robot name="plane">
<link name="planeLink">
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1.0" ixy="0" ixz="0" iyy="1.0" iyz="0" izz="1.0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane100.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -5"/>
<geometry>
<box size="500 500 10"/>
</geometry>
</collision>
</link>
</robot>

0 comments on commit e94760d

Please sign in to comment.