Skip to content
Permalink

Comparing changes

Choose two branches to see what’s changed or to start a new pull request. If you need to, you can also or learn more about diff comparisons.

Open a pull request

Create a new pull request by comparing changes across two branches. If you need to, you can also . Learn more about diff comparisons here.
base repository: leggedrobotics/legged_gym
Failed to load repositories. Confirm that selected base ref is valid, then try again.
Loading
base: master
Choose a base ref
...
head repository: LASER-Robotics/laser_legged_gym
Failed to load repositories. Confirm that selected head ref is valid, then try again.
Loading
compare: master
Choose a head ref
Able to merge. These branches can be automatically merged.
  • 6 commits
  • 14 files changed
  • 3 contributors

Commits on Dec 2, 2024

  1. Copy the full SHA
    291a006 View commit details
  2. add new task

    Augusto-Viniciuss committed Dec 2, 2024
    Copy the full SHA
    733048a View commit details
  3. bora de X?

    Futuriiiii committed Dec 2, 2024
    Copy the full SHA
    afa3fa8 View commit details

Commits on Dec 4, 2024

  1. fist train success

    Futuriiiii committed Dec 4, 2024
    Copy the full SHA
    242573b View commit details

Commits on Dec 5, 2024

  1. new tibia

    JorgeLZ13 committed Dec 5, 2024
    Copy the full SHA
    072e05b View commit details
  2. new tibia

    JorgeLZ13 committed Dec 5, 2024
    Copy the full SHA
    e34164a View commit details
5 changes: 5 additions & 0 deletions legged_gym/envs/__init__.py
Original file line number Diff line number Diff line change
@@ -31,6 +31,9 @@
from legged_gym import LEGGED_GYM_ROOT_DIR, LEGGED_GYM_ENVS_DIR
from legged_gym.envs.a1.a1_config import A1RoughCfg, A1RoughCfgPPO
from .base.legged_robot import LeggedRobot
from .guaraci.guaraci import Guaraci
from .guaraci.mixed_terrains.guaraci_rough_config import GuaraciRoughCfg, GuaraciRoughCfgPPO
from .guaraci.flat.guaraci_flat_config import GuaraciFlatCfg, GuaraciFlatCfgPPO
from .anymal_c.anymal import Anymal
from .anymal_c.mixed_terrains.anymal_c_rough_config import AnymalCRoughCfg, AnymalCRoughCfgPPO
from .anymal_c.flat.anymal_c_flat_config import AnymalCFlatCfg, AnymalCFlatCfgPPO
@@ -44,6 +47,8 @@

from legged_gym.utils.task_registry import task_registry

task_registry.register( "guaraci_rough", Guaraci, GuaraciRoughCfg(), GuaraciRoughCfgPPO() )
task_registry.register( "guaraci_flat", Guaraci, GuaraciFlatCfg(), GuaraciFlatCfgPPO() )
task_registry.register( "anymal_c_rough", Anymal, AnymalCRoughCfg(), AnymalCRoughCfgPPO() )
task_registry.register( "anymal_c_flat", Anymal, AnymalCFlatCfg(), AnymalCFlatCfgPPO() )
task_registry.register( "anymal_b", Anymal, AnymalBRoughCfg(), AnymalBRoughCfgPPO() )
4 changes: 2 additions & 2 deletions legged_gym/envs/base/legged_robot_config.py
Original file line number Diff line number Diff line change
@@ -106,7 +106,7 @@ class asset:
collapse_fixed_joints = True # merge bodies connected by fixed joints. Specific fixed joints can be kept by adding " <... dont_collapse="true">
fix_base_link = False # fixe the base of the robot
default_dof_drive_mode = 3 # see GymDofDriveModeFlags (0 is none, 1 is pos tgt, 2 is vel tgt, 3 effort)
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter
replace_cylinder_with_capsule = True # replace collision cylinders with capsules, leads to faster/more stable simulation
flip_visual_attachments = True # Some .obj meshes must be flipped from y-up to z-up

@@ -241,4 +241,4 @@ class runner:
resume = False
load_run = -1 # -1 = last run
checkpoint = -1 # -1 = last saved model
resume_path = None # updated from load_run and chkpt
resume_path = None # updated from load_run and chkpt
2 changes: 1 addition & 1 deletion legged_gym/envs/cassie/cassie_config.py
Original file line number Diff line number Diff line change
@@ -110,4 +110,4 @@ class algorithm( LeggedRobotCfgPPO.algorithm):





73 changes: 73 additions & 0 deletions legged_gym/envs/guaraci/flat/guaraci_flat_config.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
# SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: BSD-3-Clause
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice, this
# list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#
# Copyright (c) 2021 ETH Zurich, Nikita Rudin

from legged_gym.envs import GuaraciRoughCfg, GuaraciRoughCfgPPO

class GuaraciFlatCfg( GuaraciRoughCfg ):
class env( GuaraciRoughCfg.env ):
num_observations = 66

class terrain( GuaraciRoughCfg.terrain ):
mesh_type = 'plane'
measure_heights = False

class asset( GuaraciRoughCfg.asset ):
pass

class rewards( GuaraciRoughCfg.rewards ):
max_contact_force = 650.
class scales ( GuaraciRoughCfg.rewards.scales ):
orientation = -5.0
torques = -0.000025
feet_air_time = 2.
# feet_contact_forces = -0.01

class commands( GuaraciRoughCfg.commands ):
heading_command = False
resampling_time = 4.

class domain_rand( GuaraciRoughCfg.domain_rand ):
friction_range = [0., 1.5] # on ground planes the friction combination mode is averaging, i.e total friction = (foot_friction + 1.)/2.

class GuaraciFlatCfgPPO( GuaraciRoughCfgPPO ):
class policy( GuaraciRoughCfgPPO.policy ):
pass
# actor_hidden_dims = [128, 64, 32]
# critic_hidden_dims = [128, 64, 32]
# activation = 'elu' # can be elu, relu, selu, crelu, lrelu, tanh, sigmoid

# class algorithm( GuaraciRoughCfgPPO.algorithm):
# entropy_coef = 0.01

class runner ( GuaraciRoughCfgPPO.runner):
run_name = ''
experiment_name = 'flat_guaraci'
load_run = -1
max_iterations = 300
81 changes: 81 additions & 0 deletions legged_gym/envs/guaraci/guaraci.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
# SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: BSD-3-Clause
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice, this
# list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#
# Copyright (c) 2021 ETH Zurich, Nikita Rudin

from time import time
import numpy as np
import os

from isaacgym.torch_utils import *
from isaacgym import gymtorch, gymapi, gymutil

import torch
# from torch.tensor import Tensor
from typing import Tuple, Dict

from legged_gym.envs import LeggedRobot
from legged_gym import LEGGED_GYM_ROOT_DIR
from .mixed_terrains.guaraci_rough_config import GuaraciRoughCfg

class Guaraci(LeggedRobot):
cfg : GuaraciRoughCfg
def __init__(self, cfg, sim_params, physics_engine, sim_device, headless):
super().__init__(cfg, sim_params, physics_engine, sim_device, headless)

# load actuator network
if self.cfg.control.use_actuator_network:
actuator_network_path = self.cfg.control.actuator_net_file.format(LEGGED_GYM_ROOT_DIR=LEGGED_GYM_ROOT_DIR)
self.actuator_network = torch.jit.load(actuator_network_path).to(self.device)

def reset_idx(self, env_ids):
super().reset_idx(env_ids)
# Additionaly empty actuator network hidden states
self.sea_hidden_state_per_env[:, env_ids] = 0.
self.sea_cell_state_per_env[:, env_ids] = 0.

def _init_buffers(self):
super()._init_buffers()
# Additionally initialize actuator network hidden state tensors
self.sea_input = torch.zeros(self.num_envs*self.num_actions, 1, 2, device=self.device, requires_grad=False)
self.sea_hidden_state = torch.zeros(2, self.num_envs*self.num_actions, 8, device=self.device, requires_grad=False)
self.sea_cell_state = torch.zeros(2, self.num_envs*self.num_actions, 8, device=self.device, requires_grad=False)
self.sea_hidden_state_per_env = self.sea_hidden_state.view(2, self.num_envs, self.num_actions, 8)
self.sea_cell_state_per_env = self.sea_cell_state.view(2, self.num_envs, self.num_actions, 8)

def _compute_torques(self, actions):
# Choose between pd controller and actuator network
if self.cfg.control.use_actuator_network:
with torch.inference_mode():
self.sea_input[:, 0, 0] = (actions * self.cfg.control.action_scale + self.default_dof_pos - self.dof_pos).flatten()
self.sea_input[:, 0, 1] = self.dof_vel.flatten()
torques, (self.sea_hidden_state[:], self.sea_cell_state[:]) = self.actuator_network(self.sea_input, (self.sea_hidden_state, self.sea_cell_state))
return torques
else:
# pd controller
return super()._compute_torques(actions)
102 changes: 102 additions & 0 deletions legged_gym/envs/guaraci/mixed_terrains/guaraci_rough_config.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
# SPDX-FileCopyrightText: Copyright (c) 2021 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: BSD-3-Clause
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# 1. Redistributions of source code must retain the above copyright notice, this
# list of conditions and the following disclaimer.
#
# 2. Redistributions in binary form must reproduce the above copyright notice,
# this list of conditions and the following disclaimer in the documentation
# and/or other materials provided with the distribution.
#
# 3. Neither the name of the copyright holder nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
# DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
# FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
# DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
# SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
# OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#
# Copyright (c) 2021 ETH Zurich, Nikita Rudin

from legged_gym.envs.base.legged_robot_config import LeggedRobotCfg, LeggedRobotCfgPPO

class GuaraciRoughCfg( LeggedRobotCfg ):
class env( LeggedRobotCfg.env ):
num_envs = 4096
num_actions = 18
num_observations = 253

class terrain( LeggedRobotCfg.terrain ):
mesh_type = 'trimesh'

class init_state( LeggedRobotCfg.init_state ):
pos = [0.0, 0.0, 0.6] # x,y,z [m]
default_joint_angles = { # = target angles [rad] when action = 0.0
"joint_coxa_r1": 0.0,
"joint_coxa_r2": 0.0,
"joint_coxa_r3": 0.0,
"joint_coxa_l1": 0.0,
"joint_coxa_l2": 0.0,
"joint_coxa_l3": 0.0,

"joint_femur_r1": -0.368,
"joint_femur_r2": -0.368,
"joint_femur_r3": -0.368,
"joint_femur_l1": -0.368,
"joint_femur_l2": -0.368,
"joint_femur_l3": -0.368,

"joint_tibia_r1": 2.043,
"joint_tibia_r2": 2.043,
"joint_tibia_r3": 2.043,
"joint_tibia_l1": 2.043,
"joint_tibia_l2": 2.043,
"joint_tibia_l3": 2.043,
}

class control( LeggedRobotCfg.control ):
# PD Drive parameters:
stiffness = {'coxa': 40., 'femur': 40, 'tibia': 40} # [N*m/rad]
damping = {'coxa': 3., 'femur': 3., 'tibia': 3.} # [N*m*s/rad]
# action scale: target angle = actionScale * action + defaultAngle
action_scale = 0.5
# decimation: Number of control action updates @ sim DT per policy DT
decimation = 4
use_actuator_network = False
# actuator_net_file = "{LEGGED_GYM_ROOT_DIR}/resources/actuator_nets/anydrive_v3_lstm.pt"

class asset( LeggedRobotCfg.asset ):
file = "{LEGGED_GYM_ROOT_DIR}/resources/robots/guaraci/urdf/guaraci.urdf"
name = "guaraci"
foot_name = "FOOT"
penalize_contacts_on = ["femur"]
terminate_after_contacts_on = ["base"]
self_collisions = 1 # 1 to disable, 0 to enable...bitwise filter

class domain_rand( LeggedRobotCfg.domain_rand):
randomize_base_mass = False
added_mass_range = [-5., 5.]

class rewards( LeggedRobotCfg.rewards ):
base_height_target = 0.4
max_contact_force = 600.
only_positive_rewards = True
class scales( LeggedRobotCfg.rewards.scales ):
base_height = -1.2
feet_air_time = 4.

class GuaraciRoughCfgPPO( LeggedRobotCfgPPO ):
class runner( LeggedRobotCfgPPO.runner ):
run_name = ''
experiment_name = 'rough_guaraci'
load_run = -1
Loading