Unverified Commit b3bfa6e7 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Makes all configurations in locomotion velocity task consistent (#284)

# Description

This MR started with fixing the Unitree A1 environment configuration.
The asset has the name "trunk" instead of "base" so had to be adapted in
the code.

Additionally, all the ANYmal environments were following a different
hierarchy system. This MR makes the inheritance tree more consistent
across all environments.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Screenshots

All the new quadrupeds together:

![leg-suite](https://github.com/isaac-orbit/orbit/assets/12863862/3721e66b-249d-4bee-9ec5-2026c7654bc5)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent e49048f9
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.10.2"
version = "0.10.3"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.10.3 (2023-12-12)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added the attribute :attr:`omni.isaac.orbit.actuators.ActuatorNetMLPCfg.input_order`
to specify the order of the input tensors to the MLP network.
Fixed
^^^^^
* Fixed computation of metrics for the velocity command term. Earlier, the norm was being computed
over the entire batch instead of the last dimension.
* Fixed the clipping inside the :class:`omni.isaac.orbit.actuators.DCMotor` class. Earlier, it was
not able to handle the case when configured saturation limit was set to None.
0.10.2 (2023-12-12)
~~~~~~~~~~~~~~~~~~~
......
......@@ -7,6 +7,7 @@ from __future__ import annotations
from dataclasses import MISSING
from typing import Iterable
from typing_extensions import Literal
from omni.isaac.orbit.utils import configclass
......@@ -137,6 +138,16 @@ class ActuatorNetMLPCfg(DCMotorCfg):
"""Scaling of the joint velocities input to the network."""
torque_scale: float = MISSING
"""Scaling of the joint efforts output from the network."""
input_order: Literal["pos_vel", "vel_pos"] = MISSING
"""Order of the inputs to the network.
The order can be one of the following:
* ``"pos_vel"``: joint position errors followed by joint velocities
* ``"vel_pos"``: joint velocities followed by joint position errors
"""
input_idx: Iterable[int] = MISSING
"""
Indices of the actuator history buffer passed as inputs to the network.
......
......@@ -160,16 +160,23 @@ class ActuatorNetMLP(DCMotor):
# compute network inputs
# -- positions
pos_input = torch.cat([self._joint_pos_error_history[:, i].unsqueeze(2) for i in self.cfg.input_idx], dim=2)
pos_input = pos_input.reshape(self._num_envs * self.num_joints, -1)
pos_input = pos_input.view(self._num_envs * self.num_joints, -1)
# -- velocity
vel_input = torch.cat([self._joint_vel_history[:, i].unsqueeze(2) for i in self.cfg.input_idx], dim=2)
vel_input = vel_input.reshape(self._num_envs * self.num_joints, -1)
vel_input = vel_input.view(self._num_envs * self.num_joints, -1)
# -- scale and concatenate inputs
network_input = torch.cat([vel_input * self.cfg.vel_scale, pos_input * self.cfg.pos_scale], dim=1)
if self.cfg.input_order == "pos_vel":
network_input = torch.cat([pos_input * self.cfg.pos_scale, vel_input * self.cfg.vel_scale], dim=1)
elif self.cfg.input_order == "vel_pos":
network_input = torch.cat([vel_input * self.cfg.vel_scale, pos_input * self.cfg.pos_scale], dim=1)
else:
raise ValueError(
f"Invalid input order for MLP actuator net: {self.cfg.input_order}. Must be 'pos_vel' or 'vel_pos'."
)
# run network inference
torques = self.network(network_input).reshape(self._num_envs, self.num_joints)
self.computed_effort = torques.reshape(self._num_envs, self.num_joints) * self.cfg.torque_scale
torques = self.network(network_input).view(self._num_envs, self.num_joints)
self.computed_effort = torques.view(self._num_envs, self.num_joints) * self.cfg.torque_scale
# clip the computed effort based on the motor limits
self.applied_effort = self._clip_effort(self.computed_effort)
......
......@@ -210,10 +210,10 @@ class DCMotor(IdealPDActuator):
def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor:
# compute torque limits
# -- max limit
max_effort = self.cfg.saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
max_effort = self._saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
max_effort = torch.clip(max_effort, min=self._zeros_effort, max=self.effort_limit)
# -- min limit
min_effort = self.cfg.saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
min_effort = self._saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=self._zeros_effort)
# clip the torques based on the motor limits
......
......@@ -7,17 +7,43 @@
The following configurations are available:
* :obj:`UNITREE_A1_CFG`: Unitree A1 robot with simple PD controller for the legs
* :obj:`UNITREE_A1_CFG`: Unitree A1 robot with DC motor model for the legs
* :obj:`UNITREE_GO1_CFG`: Unitree Go1 robot with actuator net model for the legs
* :obj:`UNITREE_GO2_CFG`: Unitree Go2 robot with DC motor model for the legs
Reference: https://github.com/unitreerobotics/unitree_ros
"""
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators import DCMotorCfg
from omni.isaac.orbit.actuators import ActuatorNetMLPCfg, DCMotorCfg
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
from ..articulation import ArticulationCfg
##
# Configuration - Actuators.
##
GO1_ACTUATOR_CFG = ActuatorNetMLPCfg(
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
network_file=f"{ISAAC_ORBIT_NUCLEUS_DIR}/ActuatorNets/Unitree/unitree_go1.pt",
pos_scale=-1.0,
vel_scale=1.0,
torque_scale=1.0,
input_order="pos_vel",
input_idx=[0, 1, 2],
effort_limit=23.7, # taken from spec sheet
velocity_limit=30.0, # taken from spec sheet
saturation_effort=23.7, # same as effort limit
)
"""Configuration of Go1 actuators using MLP model.
Actuator specifications: https://shop.unitree.com/products/go1-motor
This model is taken from: https://github.com/Improbable-AI/walk-these-ways
"""
##
# Configuration
##
......@@ -54,7 +80,7 @@ UNITREE_A1_CFG = ArticulationCfg(
soft_joint_pos_limit_factor=0.9,
actuators={
"base_legs": DCMotorCfg(
joint_names_expr=[".*"],
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
effort_limit=33.5,
saturation_effort=33.5,
velocity_limit=21.0,
......@@ -68,3 +94,83 @@ UNITREE_A1_CFG = ArticulationCfg(
Note: Specifications taken from: https://www.trossenrobotics.com/a1-quadruped#specifications
"""
UNITREE_GO1_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/Unitree/Go1/go1.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.34),
joint_pos={
".*L_hip_joint": 0.1,
".*R_hip_joint": -0.1,
"F[L,R]_thigh_joint": 0.8,
"R[L,R]_thigh_joint": 1.0,
".*_calf_joint": -1.5,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
actuators={
"base_legs": GO1_ACTUATOR_CFG,
},
)
"""Configuration of Unitree Go1 using MLP-based actuator model."""
UNITREE_GO2_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/Unitree/Go2/go2.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.34),
joint_pos={
".*L_hip_joint": 0.1,
".*R_hip_joint": -0.1,
"F[L,R]_thigh_joint": 0.8,
"R[L,R]_thigh_joint": 1.0,
".*_calf_joint": -1.5,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
actuators={
"base_legs": DCMotorCfg(
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
effort_limit=23.5,
saturation_effort=23.5,
velocity_limit=30.0,
stiffness=25.0,
damping=0.5,
friction=0.0,
),
},
)
"""Configuration of Unitree Go2 using DC-Motor actuator model."""
......@@ -132,12 +132,13 @@ class UniformVelocityCommand(CommandTerm):
def _update_metrics(self):
# time for which the command was executed
max_command_time = self.cfg.resampling_time_range[1]
max_command_step = max_command_time / self._env.step_dt
# logs data
self.metrics["error_vel_xy"] += (
torch.norm(self.vel_command_b[:, :2] - self.robot.data.root_lin_vel_b[:, :2]) / max_command_time
torch.norm(self.vel_command_b[:, :2] - self.robot.data.root_lin_vel_b[:, :2], dim=-1) / max_command_step
)
self.metrics["error_vel_yaw"] += (
torch.abs(self.vel_command_b[:, 2] - self.robot.data.root_ang_vel_b[:, 2]) / max_command_time
torch.abs(self.vel_command_b[:, 2] - self.robot.data.root_ang_vel_b[:, 2]) / max_command_step
)
def _set_debug_vis_impl(self, debug_vis: bool):
......
......@@ -5,22 +5,15 @@
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit_tasks.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
##
# Pre-defined configs
##
from omni.isaac.orbit.assets.config.anymal import ANYMAL_B_CFG # isort: skip
from .rough_env_cfg import AnymalBRoughEnvCfg
@configclass
class AnymalBFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
class AnymalBFlatEnvCfg(AnymalBRoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# switch robot to anymal-d
self.scene.robot = ANYMAL_B_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# override rewards
self.rewards.flat_orientation_l2.weight = -5.0
self.rewards.dof_torques_l2.weight = -2.5e-5
......
......@@ -5,22 +5,15 @@
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit_tasks.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
##
# Pre-defined configs
##
from omni.isaac.orbit.assets.config.anymal import ANYMAL_C_CFG # isort: skip
from .rough_env_cfg import AnymalCRoughEnvCfg
@configclass
class AnymalCFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
class AnymalCFlatEnvCfg(AnymalCRoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# switch robot to anymal-c
self.scene.robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# override rewards
self.rewards.flat_orientation_l2.weight = -5.0
self.rewards.dof_torques_l2.weight = -2.5e-5
......
......@@ -5,22 +5,15 @@
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit_tasks.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
##
# Pre-defined configs
##
from omni.isaac.orbit.assets.config.anymal import ANYMAL_D_CFG # isort: skip
from .rough_env_cfg import AnymalDRoughEnvCfg
@configclass
class AnymalDFlatEnvCfg(LocomotionVelocityRoughEnvCfg):
class AnymalDFlatEnvCfg(AnymalDRoughEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
# switch robot to anymal-d
self.scene.robot = ANYMAL_D_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# override rewards
self.rewards.flat_orientation_l2.weight = -5.0
self.rewards.dof_torques_l2.weight = -2.5e-5
......
......@@ -20,6 +20,7 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
super().__post_init__()
self.scene.robot = UNITREE_A1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/trunk"
# scale down the terrains because the robot is small
self.scene.terrain.terrain_generator.sub_terrains["boxes"].grid_height_range = (0.025, 0.1)
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_range = (0.01, 0.06)
......@@ -30,7 +31,9 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
# randomization
self.randomization.push_robot = None
self.randomization.add_base_mass = None
self.randomization.add_base_mass.params["mass_range"] = (-1.0, 3.0)
self.randomization.add_base_mass.params["asset_cfg"].body_names = "trunk"
self.randomization.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
self.randomization.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.randomization.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
......@@ -45,7 +48,7 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
}
# rewards
self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*_calf"
self.rewards.feet_air_time.params["sensor_cfg"].body_names = ".*_foot"
self.rewards.feet_air_time.weight = 0.01
self.rewards.undesired_contacts = None
self.rewards.dof_torques_l2.weight = -0.0002
......@@ -53,6 +56,9 @@ class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
self.rewards.track_ang_vel_z_exp.weight = 0.75
self.rewards.dof_acc_l2.weight = -2.5e-7
# terminations
self.terminations.base_contact.params["sensor_cfg"].body_names = "trunk"
@configclass
class UnitreeA1RoughEnvCfg_PLAY(UnitreeA1RoughEnvCfg):
......
......@@ -235,7 +235,7 @@ class RewardsCfg:
func=mdp.feet_air_time,
weight=0.5,
params={
"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*SHANK"),
"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*FOOT"),
"command_name": "base_velocity",
"threshold": 0.5,
},
......@@ -278,7 +278,7 @@ class LocomotionVelocityRoughEnvCfg(RLTaskEnvCfg):
"""Configuration for the locomotion velocity-tracking environment."""
# Scene settings
scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5, replicate_physics=False)
scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5)
# Basic settings
observations: ObservationsCfg = ObservationsCfg()
actions: ActionsCfg = ActionsCfg()
......
......@@ -45,7 +45,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import Articulation
from omni.isaac.orbit.assets.config.anymal import ANYMAL_B_CFG, ANYMAL_C_CFG, ANYMAL_D_CFG
from omni.isaac.orbit.assets.config.unitree import UNITREE_A1_CFG
from omni.isaac.orbit.assets.config.unitree import UNITREE_A1_CFG, UNITREE_GO1_CFG, UNITREE_GO2_CFG
def define_origins(num_origins: int, spacing: float) -> list[list[float]]:
......@@ -74,7 +74,7 @@ def design_scene() -> tuple[dict, list[list[float]]]:
# Create separate groups called "Origin1", "Origin2", "Origin3"
# Each group will have a mount and a robot on top of it
origins = define_origins(num_origins=4, spacing=1.25)
origins = define_origins(num_origins=6, spacing=1.25)
# Origin 1 with Anymal B
prim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
......@@ -96,8 +96,25 @@ def design_scene() -> tuple[dict, list[list[float]]]:
# -- Robot
unitree_a = Articulation(UNITREE_A1_CFG.replace(prim_path="/World/Origin4/Robot"))
# Origin 5 with Unitree Go1
prim_utils.create_prim("/World/Origin5", "Xform", translation=origins[4])
# -- Robot
unitree_go1 = Articulation(UNITREE_GO1_CFG.replace(prim_path="/World/Origin5/Robot"))
# Origin 6 with Unitree Go2
prim_utils.create_prim("/World/Origin6", "Xform", translation=origins[5])
# -- Robot
unitree_go2 = Articulation(UNITREE_GO2_CFG.replace(prim_path="/World/Origin6/Robot"))
# return the scene information
scene_entities = {"anymal_b": anymal_b, "anymal_c": anymal_c, "anymal_d": anymal_d, "unitree_a": unitree_a}
scene_entities = {
"anymal_b": anymal_b,
"anymal_c": anymal_c,
"anymal_d": anymal_d,
"unitree_a": unitree_a,
"unitree_go1": unitree_go1,
"unitree_go2": unitree_go2,
}
return scene_entities, origins
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment