Unverified Commit 4ba7a0f0 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Merges refactorings for locomotion environment training (#93)

# Description

This MR merges all the refactorings done to make the legged locomotion
environment training work. It includes the following:
* `ActionManager` class: To handle various action terms and provide
flexibility for HRL.
* Actuator simplification: We no longer have actuator groups. All that
is handled externally to the robot.
* Sensor optimization: Lazy sensor updates (only updated when `data` is
called)
* Update to new RSL-RL library
* TerrainImporter: It does import on initialization instead of expecting
input from users.

This MR breaks the behavior of the following (many of which need to be
fixed):
* `RobotBase` : Now there are two methods `write_commands_to_sim` and
`refresh_sim_data` that dictate sim read/write.
* `ActuatorGroups`: Doesn't exist anymore.
* `SensorBase`: Drop for the support of different backends (was not
supported earlier but now more explicit)

Fixes #37 , #36 

## Type of change

- Bug fix (non-breaking change which fixes an issue)
- New feature (non-breaking change which adds functionality)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- This change requires a documentation update

## 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
- [ ] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file

---------
Co-authored-by: 's avatarDavid Hoeller <dhoeller@ethz.ch>
Co-authored-by: 's avatarNikita Rudin <nrudin@nvidia.com>
Co-authored-by: 's avatarFarbod Farshidian <ffarshidian@theaiinstitute.com>
parent a9de59fe
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.7.4"
version = "0.8.0"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.8.0 (2023-07-26)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added the :class:`ActionManager` class to the :mod:`omni.isaac.orbit.managers` module to handle actions in the
environment through action terms.
* Added contact force history to the :class:`omni.isaac.orbit.sensors.ContactSensor` class. The history is stored
in the ``net_forces_w_history`` attribute of the sensor data.
Changed
^^^^^^^
* Implemented lazy update of buffers in the :class:`omni.isaac.orbit.sensors.SensorBase` class. This allows the user
to update the sensor data only when required, i.e. when the data is requested by the user. This helps avoid double
computation of sensor data when a reset is called in the environment.
Deprecated
^^^^^^^^^^
* Removed the support for different backends in the sensor class. We only use Pytorch as the backend now.
* Removed the concept of actuator groups. They are now handled by the :class:`omni.isaac.orbit.managers.ActionManager`
class. The actuator models are now directly handled by the robot class itself.
0.7.4 (2023-07-26)
~~~~~~~~~~~~~~~~~~
......@@ -99,7 +126,7 @@ Fixed
* Fixed the :meth:`omni.isaac.orbit.utils.math.quat_apply_yaw` to compute the yaw quaternion correctly.
Added
^^^^^^^
^^^^^
* Added functions to convert string and callable objects in :mod:`omni.isaac.orbit.utils.string`.
......
......@@ -3,7 +3,8 @@
#
# SPDX-License-Identifier: BSD-3-Clause
"""Subpackage for handling actuator models and groups."""
"""Subpackage for handling actuator models."""
from .group import *
from .model import *
from .actuator import ActuatorBase, DCMotor, IdealPDActuator, ImplicitActuator
from .actuator_cfg import ActuatorBaseCfg, ActuatorNetLSTMCfg, ActuatorNetMLPCfg, DCMotorCfg, IdealPDActuatorCfg
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
......@@ -3,118 +3,94 @@
#
# SPDX-License-Identifier: BSD-3-Clause
import torch
from __future__ import annotations
from dataclasses import MISSING
from typing import Callable, ClassVar, Iterable, Optional, Union
from typing import Iterable
from omni.isaac.orbit.utils import configclass
from .actuator import ActuatorBase, DCMotor, IdealPDActuator, ImplicitActuator
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
@configclass
class BaseActuatorCfg:
"""Base configuration for actuator model.
class ActuatorBaseCfg:
"""Configuration for default actuators in an articulation."""
Note:
This class is not meant to be instantiated directly, i.e., it should
only by used as a base class for other actuator model configurations.
"""
cls: type[ActuatorBase] = MISSING
"""Actuator class."""
cls_name: ClassVar[Optional[str]] = MISSING
"""
Name of the associated actuator class.
dof_name_expr: list[str] = MISSING
"""Articulation's DOF names that are part of the group. Can be regex expressions (e.g. ".*")."""
This is used to construct the actuator model. If an "implicit" model, then the class name
is :obj:`None`. Otherwise, it is the name of the actuator model class.
effort_limit: float | None = None
"""
model_type: ClassVar[str] = MISSING
"""Type of actuator model: "explicit" or "implicit"."""
"""
Actuator model configurations.
"""
@configclass
class ImplicitActuatorCfg(BaseActuatorCfg):
"""Configuration for implicit actuator model.
Note:
There are no classes associated to this model. It is handled directly by the physics
simulation. The provided configuration is used to set the physics simulation parameters.
Force/Torque limit of the DOFs in the group. Defaults to :obj:`None`.
"""
cls_name: ClassVar[Optional[str]] = None # implicit actuators are handled directly.
model_type: ClassVar[str] = "implicit"
torque_limit: Optional[float] = None
velocity_limit: float | None = None
"""
Torque saturation (in N-m). Defaults to :obj:`None`.
This is used by the physics simulation. If :obj:`None`, then default values from USD is used.
Velocity limit of the DOFs in the group. Defaults to :obj:`None`.
"""
# TODO (@mayank): Check if we can remove this parameter and use the default values?
velocity_limit: Optional[float] = None
stiffness: dict[str, float] | None = None
"""
Stiffness gains (Also known as P gain) of the DOFs in the group. Defaults to :obj:`None`.
If :obj:`None`, these are loaded from the articulation prim.
"""
Velocity saturation (in rad/s or m/s). Defaults to :obj:`None`.
This is used by the physics simulation. If :obj:`None`, then default values from USD is used.
Tip:
Setting this parameter low may result in undesired behaviors. Keep it high in general.
damping: dict[str, float] | None = None
"""
Damping gains (Also known as D gain) of the DOFs in the group. Defaults to :obj:`None`.
If :obj:`None`, these are loaded from the articulation prim.
"""
@configclass
class IdealActuatorCfg(BaseActuatorCfg):
"""Configuration for ideal actuator model."""
class IdealPDActuatorCfg(ActuatorBaseCfg):
"""Configuration for an ideal PD actuator.
The PD control is handled implicitly by the simulation."""
cls_name: ClassVar[str] = "IdealActuator"
model_type: ClassVar[str] = "explicit"
cls: type[ActuatorBase] = IdealPDActuator
"""Actuator class."""
motor_torque_limit: float = MISSING
"""Effort limit on the motor controlling the actuator (in N-m)."""
gear_ratio: float = 1.0
"""The gear ratio of the gear box from motor to joint axel. Defaults to 1.0."""
@configclass
class ImplicitPDActuatorCfg(ActuatorBaseCfg):
"""Configuration for an ideal PD actuator.
The PD control is handled implicitly by the simulation."""
cls: type[ActuatorBase] = ImplicitActuator
"""Actuator class."""
@configclass
class DCMotorCfg(IdealActuatorCfg):
class DCMotorCfg(IdealPDActuatorCfg):
"""Configuration for direct control (DC) motor actuator model."""
cls_name: ClassVar[str] = "DCMotor"
cls: type[ActuatorBase] = DCMotor
"""Actuator class."""
peak_motor_torque: float = MISSING
"""Peak motor torque of the electric DC motor (in N-m)."""
motor_velocity_limit: float = MISSING
"""Maximum velocity of the motor controlling the actuated joint (in rad/s)."""
saturation_effort: float = MISSING
"""Peak motor force/torque of the electric DC motor (in N-m)."""
@configclass
class VariableGearRatioDCMotorCfg(DCMotorCfg):
"""Configuration for variable gear-ratio DC motor actuator model."""
cls_name: ClassVar[str] = "VariableGearRatioDCMotor"
class ActuatorNetLSTMCfg(DCMotorCfg):
"""Configuration for LSTM-based actuator model."""
# gear ratio is a function of dof positions
gear_ratio: Union[str, Callable[[torch.Tensor], torch.Tensor]] = MISSING
"""
Gear ratio function of the gear box connecting the motor to actuated joint.
cls: type[ActuatorBase] = ActuatorNetLSTM
Note:
The gear ratio function takes as input the joint positions.
"""
network_file: str = MISSING
"""Path to the file containing network weights."""
@configclass
class ActuatorNetMLPCfg(DCMotorCfg):
"""Configuration for MLP-based actuator model."""
cls_name: ClassVar[str] = "ActuatorNetMLP"
cls: type[ActuatorBase] = ActuatorNetMLP
network_file: str = MISSING
"""Path to the file containing network weights."""
......@@ -132,13 +108,3 @@ class ActuatorNetMLPCfg(DCMotorCfg):
The index *0* corresponds to current time-step, while *n* corresponds to n-th
time-step in the past. The allocated history length is `max(input_idx) + 1`.
"""
@configclass
class ActuatorNetLSTMCfg(DCMotorCfg):
"""Configuration for LSTM-based actuator model."""
cls_name: ClassVar[str] = "ActuatorNetLSTM"
network_file: str = MISSING
"""Path to the file containing network weights."""
......@@ -7,13 +7,10 @@
Submodule containing configuration instances for commonly used robots.
"""
from .anydrive import ANYDRIVE_3_ACTUATOR_CFG, ANYDRIVE_SIMPLE_ACTUATOR_CFG
from .franka import PANDA_HAND_MIMIC_GROUP_CFG
from .anydrive import Anydrive3LSTMCfg, Anydrive3SimpleCfg
__all__ = [
# ANYmal actuators
"ANYDRIVE_SIMPLE_ACTUATOR_CFG",
"ANYDRIVE_3_ACTUATOR_CFG",
# Franka panda actuators
"PANDA_HAND_MIMIC_GROUP_CFG",
"Anydrive3LSTMCfg",
"Anydrive3SimpleCfg",
]
......@@ -15,44 +15,29 @@ The following actuator groups are available:
* ANYmal-C default actuator group that uses ANYdrive 3.0 with LSTM actuator model.
"""
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, ActuatorGroupCfg
from omni.isaac.orbit.actuators.model import ActuatorNetLSTMCfg, DCMotorCfg
from omni.isaac.orbit.actuators import ActuatorNetLSTMCfg, DCMotorCfg
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
"""
Actuator Models.
"""
ANYDRIVE_SIMPLE_ACTUATOR_CFG = DCMotorCfg(
peak_motor_torque=120.0, motor_torque_limit=80.0, motor_velocity_limit=7.5, gear_ratio=1.0
)
"""Configuration for ANYdrive 3.x with DC actuator model."""
ANYDRIVE_3_ACTUATOR_CFG = ActuatorNetLSTMCfg(
network_file=f"{ISAAC_ORBIT_NUCLEUS_DIR}/ActuatorNets/anydrive_3_lstm_jit.pt",
peak_motor_torque=120.0,
motor_torque_limit=89.0,
motor_velocity_limit=7.5,
gear_ratio=1.0,
)
"""Configuration for ANYdrive 3.0 (used on ANYmal-C) with LSTM actuator model."""
@configclass
class Anydrive3SimpleCfg(DCMotorCfg):
"""Simple ANYdrive 3.0 model with only DC Motor limits."""
"""
Actuator Groups.
"""
saturation_effort: float = 120.0
effort_limit: float = 80.0
velocity_limit: float = 7.5
@configclass
class Anydrive3LSTMCfg(ActuatorNetLSTMCfg):
"""ANYdrive 3 model represented by an LSTM network trained from real data."""
ANYMAL_C_DEFAULT_GROUP_CFG = ActuatorGroupCfg(
dof_names=[".*HAA", ".*HFE", ".*KFE"],
model_cfg=ANYDRIVE_3_ACTUATOR_CFG,
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
dof_pos_offset={
".*HAA": 0.0, # all HAA
".*F_HFE": 0.4, # both front HFE
".*H_HFE": -0.4, # both hind HFE
".*F_KFE": -0.8,
".*H_KFE": 0.8,
},
),
)
"""Configuration for default ANYmal-C quadruped with LSTM actuator network."""
network_file: str = f"{ISAAC_ORBIT_NUCLEUS_DIR}/ActuatorNets/anydrive_3_lstm_jit.pt"
saturation_effort: float = 120.0
effort_limit: float = 80.0
velocity_limit: float = 7.5
......@@ -3,20 +3,20 @@
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, GripperActuatorGroupCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.actuators.group import ActuatorControlCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
"""
Actuator Groups.
"""
PANDA_HAND_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=["panda_finger_joint[1-2]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=0.2, torque_limit=200),
control_cfg=ActuatorControlCfg(command_types=["p_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={"panda_finger_joint.*": 1.0},
speed=0.1,
open_dof_pos=0.04,
close_dof_pos=0.0,
)
"""Configuration for Franka Panda hand with implicit actuator model."""
# PANDA_HAND_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=["panda_finger_joint[1-2]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=0.2, torque_limit=200),
# control_cfg=ActuatorControlCfg(command_types=["p_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={"panda_finger_joint.*": 1.0},
# speed=0.1,
# open_dof_pos=0.04,
# close_dof_pos=0.0,
# )
# """Configuration for Franka Panda hand with implicit actuator model."""
......@@ -3,31 +3,31 @@
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, GripperActuatorGroupCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.actuators.group import ActuatorControlCfg, GripperActuatorGroupCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
"""
Actuator Groups.
"""
KINOVA_S300_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=[".*_joint_finger_[1-3]", ".*_joint_finger_tip_[1-3]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=1.0, torque_limit=2.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={".*_joint_finger_[1-3]": 1.0, ".*_joint_finger_tip_[1-3]": 0.0},
speed=0.1,
open_dof_pos=0.65,
close_dof_pos=0.0,
)
"""Configuration for Kinova S300 hand with implicit actuator model."""
# KINOVA_S300_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=[".*_joint_finger_[1-3]", ".*_joint_finger_tip_[1-3]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=1.0, torque_limit=2.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={".*_joint_finger_[1-3]": 1.0, ".*_joint_finger_tip_[1-3]": 0.0},
# speed=0.1,
# open_dof_pos=0.65,
# close_dof_pos=0.0,
# )
# """Configuration for Kinova S300 hand with implicit actuator model."""
KINOVA_S200_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=[".*_joint_finger_[1-2]", ".*_joint_finger_tip_[1-2]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=1.0, torque_limit=2.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={".*_joint_finger_[1-2]": 1.0, ".*_joint_finger_tip_[1-2]": 0.0},
speed=0.1,
open_dof_pos=0.65,
close_dof_pos=0.0,
)
"""Configuration for Kinova S200 hand with implicit actuator model."""
# KINOVA_S200_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=[".*_joint_finger_[1-2]", ".*_joint_finger_tip_[1-2]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=1.0, torque_limit=2.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={".*_joint_finger_[1-2]": 1.0, ".*_joint_finger_tip_[1-2]": 0.0},
# speed=0.1,
# open_dof_pos=0.65,
# close_dof_pos=0.0,
# )
# """Configuration for Kinova S200 hand with implicit actuator model."""
......@@ -3,57 +3,57 @@
#
# SPDX-License-Identifier: BSD-3-Clause
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, GripperActuatorGroupCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.actuators.group import ActuatorControlCfg, GripperActuatorGroupCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
"""
Actuator Groups.
"""
ROBOTIQ_2F140_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=["finger_joint", ".*_inner_knuckle_joint", ".*_inner_finger_joint", ".*right_outer_knuckle_joint"],
model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={
"finger_joint": 1.0, # mimicked joint
".*_inner_knuckle_joint": -1.0,
".*_inner_finger_joint": 1.0,
".*right_outer_knuckle_joint": -1.0,
},
speed=0.01,
open_dof_pos=0.7,
close_dof_pos=0.0,
)
"""Configuration for Robotiq 2F-140 gripper with implicit actuator model."""
# ROBOTIQ_2F140_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=["finger_joint", ".*_inner_knuckle_joint", ".*_inner_finger_joint", ".*right_outer_knuckle_joint"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={
# "finger_joint": 1.0, # mimicked joint
# ".*_inner_knuckle_joint": -1.0,
# ".*_inner_finger_joint": 1.0,
# ".*right_outer_knuckle_joint": -1.0,
# },
# speed=0.01,
# open_dof_pos=0.7,
# close_dof_pos=0.0,
# )
# """Configuration for Robotiq 2F-140 gripper with implicit actuator model."""
ROBOTIQ_2F85_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=["finger_joint", ".*_inner_knuckle_joint", ".*_inner_finger_joint", ".*right_outer_knuckle_joint"],
model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={
"finger_joint": 1.0, # mimicked joint
".*_inner_knuckle_joint": 1.0,
".*_inner_finger_joint": -1.0,
".*right_outer_knuckle_joint": 1.0,
},
speed=0.01,
open_dof_pos=0.8,
close_dof_pos=0.0,
)
"""Configuration for Robotiq 2F-85 gripper with implicit actuator model."""
# ROBOTIQ_2F85_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=["finger_joint", ".*_inner_knuckle_joint", ".*_inner_finger_joint", ".*right_outer_knuckle_joint"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={
# "finger_joint": 1.0, # mimicked joint
# ".*_inner_knuckle_joint": 1.0,
# ".*_inner_finger_joint": -1.0,
# ".*right_outer_knuckle_joint": 1.0,
# },
# speed=0.01,
# open_dof_pos=0.8,
# close_dof_pos=0.0,
# )
# """Configuration for Robotiq 2F-85 gripper with implicit actuator model."""
ROBOTIQ_C2_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
dof_names=[".*_left_knuckle_joint", ".*_right_knuckle_joint", ".*_inner_knuckle_joint", ".*_finger_tip_joint"],
model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
mimic_multiplier={
".*_left_knuckle_joint": 1.0, # mimicked joint
".*_right_knuckle_joint": 1.0,
".*_inner_knuckle_joint": 1.0,
".*_finger_tip_joint": -1.0,
},
speed=0.01,
open_dof_pos=0.85,
close_dof_pos=0.0,
)
"""Configuration for Robotiq C2 gripper with implicit actuator model."""
# ROBOTIQ_C2_MIMIC_GROUP_CFG = GripperActuatorGroupCfg(
# dof_names=[".*_left_knuckle_joint", ".*_right_knuckle_joint", ".*_inner_knuckle_joint", ".*_finger_tip_joint"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=2.0, torque_limit=1000.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 1e5}, damping={".*": 1e3}),
# mimic_multiplier={
# ".*_left_knuckle_joint": 1.0, # mimicked joint
# ".*_right_knuckle_joint": 1.0,
# ".*_inner_knuckle_joint": 1.0,
# ".*_finger_tip_joint": -1.0,
# },
# speed=0.01,
# open_dof_pos=0.85,
# close_dof_pos=0.0,
# )
# """Configuration for Robotiq C2 gripper with implicit actuator model."""
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""This module contains the configuration classes and explicit models for actuators."""
from .actuator_cfg import (
ActuatorNetLSTMCfg,
ActuatorNetMLPCfg,
DCMotorCfg,
IdealActuatorCfg,
ImplicitActuatorCfg,
VariableGearRatioDCMotorCfg,
)
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
from .actuator_physics import DCMotor, IdealActuator, VariableGearRatioDCMotor
__all__ = [
# implicit
"ImplicitActuatorCfg",
# ideal actuator
"IdealActuatorCfg",
"IdealActuator",
# dc motor
"DCMotorCfg",
"DCMotor",
# variable gear
"VariableGearRatioDCMotorCfg",
"VariableGearRatioDCMotor",
# mlp
"ActuatorNetMLPCfg",
"ActuatorNetMLP",
# lstm
"ActuatorNetLSTMCfg",
"ActuatorNetLSTM",
]
......@@ -79,7 +79,7 @@ class TerrainBasedPositionCommandGenerator(CommandGeneratorBase):
marker_cfg = CUBOID_MARKER_CFG
marker_cfg.markers["cuboid"].color = (1.0, 0.0, 0.0)
marker_cfg.markers["cuboid"].scale = (0.1, 0.1, 0.1)
self._box_goal_marker = VisualizationMarkers("/Visuals/base_position_goal", marker_cfg)
self._box_goal_marker = VisualizationMarkers("/Visuals/Command/position_goal", marker_cfg)
# update the box marker
self._box_goal_marker.visualize(self.pos_command_w)
......
......@@ -91,11 +91,11 @@ class UniformVelocityCommandGenerator(CommandGeneratorBase):
if self._base_vel_goal_markers is None:
marker_cfg = ARROW_X_MARKER_CFG
marker_cfg.markers["arrow"].color = (1.0, 0.0, 0.0)
self._base_vel_goal_markers = VisualizationMarkers("/Visuals/base_velocity_goal", marker_cfg)
self._base_vel_goal_markers = VisualizationMarkers("/Visuals/Command/velocity_goal", marker_cfg)
if self._base_vel_markers is None:
marker_cfg = ARROW_X_MARKER_CFG
marker_cfg.markers["arrow"].color = (0.0, 0.0, 1.0)
self._base_vel_markers = VisualizationMarkers("/Visuals/base_velocity_current", marker_cfg)
self._base_vel_markers = VisualizationMarkers("/Visuals/Command/velocity_current", marker_cfg)
# get marker location
# -- base state
base_pos_w = self.robot.data.root_pos_w.clone()
......
......@@ -14,8 +14,6 @@ Module containing different actuator groups.
from .actuator_control_cfg import ActuatorControlCfg
from .actuator_group import ActuatorGroup
from .actuator_group_cfg import ActuatorGroupCfg, GripperActuatorGroupCfg, NonHolonomicKinematicsGroupCfg
from .gripper_group import GripperActuatorGroup
from .non_holonomic_group import NonHolonomicKinematicsGroup
__all__ = [
# control
......@@ -23,10 +21,4 @@ __all__ = [
# default
"ActuatorGroupCfg",
"ActuatorGroup",
# mimic
"GripperActuatorGroupCfg",
"GripperActuatorGroup",
# non-holonomic
"NonHolonomicKinematicsGroupCfg",
"NonHolonomicKinematicsGroup",
]
......@@ -53,31 +53,3 @@ class ActuatorControlCfg:
If :obj:`None`, these are loaded from the articulation prim.
"""
dof_pos_offset: Optional[Dict[str, float]] = None
"""
DOF position offsets used for processing commands. Defaults to :obj:`None`.
If :obj:`None`, these are processed as zero, i.e. absolute commands.
"""
dof_pos_scale: Optional[Dict[str, float]] = None
"""
DOF position scaling factor used for processing commands. Defaults to :obj:`None`.
If :obj:`None`, these are processed as ones, i.e. absolute commands.
"""
dof_vel_scale: Optional[Dict[str, float]] = None
"""
DOF velocity scaling factor used for processing commands. Defaults to :obj:`None`.
If :obj:`None`, these are processed as ones, i.e. absolute commands.
"""
dof_torque_scale: Optional[Dict[str, float]] = None
"""
DOF torque scaling factor used for processing commands. Defaults to :obj:`None`.
If :obj:`None`, these are processed as ones, i.e. absolute commands.
"""
......@@ -37,7 +37,7 @@ class ActuatorGroup:
"""The configuration of the actuator group."""
view: ArticulationView
"""The simulation articulation view."""
num_articulations: int
num_articulation: int
"""Number of articulations in the view."""
device: str
"""Device used for processing."""
......@@ -46,19 +46,7 @@ class ActuatorGroup:
dof_indices: List[int]
"""Articulation's DOF indices that are part of the group."""
model: Optional[IdealActuator]
"""Actuator model used by the group.
If model type is "implicit" (i.e., when :obj:`ActuatorGroupCfg.model_cfg` is instance of
:class:`ImplicitActuatorCfg`), then `model` is set to :obj:`None`.
"""
dof_pos_offset: torch.Tensor
"""DOF position offsets used for processing commands."""
dof_pos_scale: torch.Tensor
"""DOF position scale used for processing commands."""
dof_vel_scale: torch.Tensor
"""DOF velocity scale used for processing commands."""
dof_torque_scale: torch.Tensor
"""DOF torque scale used for processing commands."""
"""Actuator model used by the group."""
def __init__(self, cfg: ActuatorGroupCfg, view: ArticulationView):
"""Initialize the actuator group.
......@@ -365,7 +353,7 @@ class ActuatorGroup:
Returns:
torch.Tensor: Desired commands for the DOFs in the group.
Shape is ``(num_articulations, num_actuators * len(command_types))``.
Shape is ``(num_articulation, num_actuators * len(command_types))``.
"""
return command
......
......@@ -33,8 +33,10 @@ Example pseudo-code for a manager:
"""
from .action_manager import ActionManager, ActionTerm
from .curriculum_manager import CurriculumManager
from .manager_cfg import (
ActionTermCfg,
CurriculumTermCfg,
ObservationGroupCfg,
ObservationTermCfg,
......@@ -48,6 +50,10 @@ from .reward_manager import RewardManager
from .termination_manager import TerminationManager
__all__ = [
# action
"ActionTermCfg",
"ActionTerm",
"ActionManager",
# curriculum
"CurriculumTermCfg",
"CurriculumManager",
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Action manager for processing actions sent to the environment."""
from __future__ import annotations
import torch
from abc import ABC, abstractmethod
from prettytable import PrettyTable
from .manager_base import ManagerBase
from .manager_cfg import ActionTermCfg
class ActionTerm(ABC):
"""Base class for action terms."""
# TODO: Should this be here or a property?
# Are they even exposed to the user?
raw_actions: torch.Tensor
processed_actions: torch.Tensor
def __init__(self, cfg: ActionTermCfg, env: object):
"""Initialize the action term.
Args:
cfg (ActionTermCfg): The configuration object.
env (object): The environment instance.
"""
# store the inputs
self._cfg = cfg
self._env = env
# parse config to obtain asset to which the term is applied
self._asset = getattr(env, cfg.asset_name)
"""
Properties.
"""
@property
def num_envs(self) -> int:
"""Number of environments."""
return self._env.num_envs
@property
def device(self) -> str:
"""Device on which to perform computations."""
return self._env.device
@property
@abstractmethod
def action_dim(self) -> int:
"""Dimension of the action term."""
raise NotImplementedError
"""
Operations.
"""
def process_actions(self, actions: torch.Tensor):
"""Processes the actions sent to the environment.
Note:
This function is called once per environment step by the manager.
Args:
actions (torch.Tensor): The actions to process.
"""
# TODO: Why not make this an abstract method?
# This one line can be implemented in the child class.
self.raw_actions[:] = actions
@abstractmethod
def apply_actions(self):
"""Applies the actions to the asset managed by the term.
Note:
This is called at every simulation step by the manager.
"""
raise NotImplementedError
class ActionManager(ManagerBase):
"""Manager for processing and applying actions for a given world.
The action manager handles the interpretation and application of user-defined
actions on a given world. It is comprised of different action terms that decide
the dimension of the expected actions.
The action manager performs operations at two stages:
* processing of actions: It splits the input actions to each term and performs any
pre-processing needed. This should be called once at every environment step.
* apply actions: This operation typically sets the processed actions into the assets in the
scene (such as robots). It should be called before every simulation step.
"""
def __init__(self, cfg: object, env: object):
"""Initialize the action manager.
Args:
cfg (object): The configuration object or dictionary (``dict[str, ActionTermCfg]``).
env (object): The environment instance.
"""
super().__init__(cfg, env)
def __str__(self) -> str:
"""Returns: A string representation for action manager."""
msg = f"<ActionManager> contains {len(self._term_names)} active terms.\n"
# create table for term information
table = PrettyTable()
table.title = f"Active Action Terms (shape: {self.total_action_dim})"
table.field_names = ["Index", "Name", "Dimension"]
# set alignment of table columns
table.align["Name"] = "l"
table.align["Dimension"] = "r"
# add info on each term
for index, (name, term) in enumerate(zip(self._term_names, self._terms)):
table.add_row([index, name, term.action_dim])
# convert table to string
msg += table.get_string()
return msg
"""
Properties.
"""
@property
def total_action_dim(self) -> int:
"""Total dimension of actions."""
return sum(self.action_term_dim)
@property
def active_terms(self) -> list[str]:
"""Name of active action terms."""
return self._term_names
@property
def action_term_dim(self) -> list[int]:
"""Shape of each action term."""
return [term.action_dim for term in self._terms]
"""
Operations.
"""
def process_actions(self, actions: torch.Tensor):
"""Processes the actions sent to the environment.
Note:
This function should be called once per environment step.
Args:
actions (torch.Tensor): The actions to process.
"""
# check if action dimension is valid
if self.total_action_dim != actions.shape[1]:
raise ValueError(f"Invalid action shape, expected: {self.total_action_dim}, received: {actions.shape[1]}")
# split the actions and apply to each tensor
idx = 0
for term in self._terms:
term_actions = actions[:, idx : idx + term.action_dim]
term.process_actions(term_actions)
def apply_actions(self) -> None:
"""Applies the actions to the environment/simulation.
Note:
This should be called at every simulation step.
"""
for term in self._terms:
term.apply_actions()
"""
Helper functions.
"""
def _prepare_terms(self):
"""Prepares a list of action terms."""
# parse action terms from the config
self._term_names: list[str] = list()
self._terms: list[ActionTerm] = list()
# check if config is dict already
if isinstance(self.cfg, dict):
cfg_items = self.cfg.items()
else:
cfg_items = self.cfg.__dict__.items()
for term_name, term_cfg in cfg_items:
# check valid type
if not isinstance(term_cfg, ActionTermCfg):
raise TypeError(
f"Configuration for the term '{term_name}' is not of type ActionTermCfg. Received '{type(term_cfg)}'."
)
# create the action term
term = term_cfg.cls(term_cfg, self._env)
# sanity check if term is valid type
if not isinstance(term, ActionTerm):
raise TypeError(f"Returned object for the term '{term_name}' is not of type ActionType.")
# add term name and parameters
self._term_names.append(term_name)
self._terms.append(term)
......@@ -10,11 +10,14 @@ from __future__ import annotations
import torch
from dataclasses import MISSING
from typing import Any, Callable, Sequence
from typing import TYPE_CHECKING, Any, Callable, Sequence
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit.utils.noise import NoiseCfg
if TYPE_CHECKING:
from .action_manager import ActionTerm
@configclass
class ManagerBaseTermCfg:
......@@ -53,6 +56,20 @@ class ManagerBaseTermCfg:
"""The parameters to be passed to the function as keyword arguments. Defaults to an empty dict."""
"""Action manager."""
@configclass
class ActionTermCfg:
"""Configuration for an action term."""
cls: type[ActionTerm] = MISSING
"""Class of the action term."""
asset_name: str = MISSING
"""Name of the asset (object or robot) on which action is applied."""
"""Curriculum manager."""
......
......@@ -5,7 +5,7 @@
import re
import torch
from typing import Dict, List, Optional, Sequence, Tuple
from typing import Dict, List, Optional, Sequence
import carb
import omni.isaac.core.utils.prims as prim_utils
......@@ -14,7 +14,7 @@ from omni.isaac.core.prims import RigidPrimView
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.actuators.group import * # noqa: F403, F401
from omni.isaac.orbit.utils.math import quat_rotate_inverse, sample_uniform, subtract_frame_transforms
from omni.isaac.orbit.utils.math import quat_rotate_inverse, subtract_frame_transforms
from .articulated_object_cfg import ArticulatedObjectCfg
from .articulated_object_data import ArticulatedObjectData
......@@ -312,68 +312,6 @@ class ArticulatedObject:
self._data.dof_vel[env_ids] = dof_vel.clone()
self._data.dof_acc[env_ids] = 0.0
def get_default_dof_state(
self, env_ids: Optional[Sequence[int]] = None, clone=True
) -> Tuple[torch.Tensor, torch.Tensor]:
"""Returns the default/initial DOF state (position and velocity) of actor.
Args:
env_ids (Optional[Sequence[int]], optional): Environment indices.
Defaults to None (all environment indices).
clone (bool, optional): Whether to return a copy or not. Defaults to True.
Returns:
Tuple[torch.Tensor, torch.Tensor]: The default/initial DOF position and velocity of the actor.
Each tensor has shape: (len(env_ids), 1).
"""
# use ellipses object to skip initial indices.
if env_ids is None:
env_ids = ...
# return copy
if clone:
return torch.clone(self._default_dof_pos[env_ids]), torch.clone(self._default_dof_vel[env_ids])
else:
return self._default_dof_pos[env_ids], self._default_dof_vel[env_ids]
def get_random_dof_state(
self, env_ids: Optional[Sequence[int]] = None, lower: float = 0.5, upper: float = 1.5
) -> Tuple[torch.Tensor, torch.Tensor]:
"""Returns randomly sampled DOF state (position and velocity) of actor.
Currently, the following sampling is supported:
- DOF positions:
- uniform sampling between `(lower, upper)` times the default DOF position.
- DOF velocities:
- zero.
Args:
env_ids (Optional[Sequence[int]], optional): Environment indices.
Defaults to None (all environment indices).
lower (float, optional): Minimum value for uniform sampling. Defaults to 0.5.
upper (float, optional): Maximum value for uniform sampling. Defaults to 1.5.
Returns:
Tuple[torch.Tensor, torch.Tensor]: The sampled DOF position and velocity of the actor.
Each tensor has shape: (len(env_ids), 1).
"""
# use ellipses object to skip initial indices.
if env_ids is None:
env_ids = ...
actor_count = self.count
else:
actor_count = len(env_ids)
# sample DOF position
dof_pos = self._default_dof_pos[env_ids] * sample_uniform(
lower, upper, (actor_count, self.num_dof), device=self.device
)
dof_vel = self._default_dof_vel[env_ids]
# return sampled dof state
return dof_pos, dof_vel
"""
Internal helper.
"""
......@@ -392,17 +330,17 @@ class ArticulatedObject:
self._default_root_states = torch.tensor(default_root_state, dtype=torch.float, device=self.device)
self._default_root_states = self._default_root_states.repeat(self.count, 1)
# -- dof state
self._default_dof_pos = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)
self._default_dof_vel = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)
self._data.default_dof_pos = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)
self._data.default_dof_vel = torch.zeros(self.count, self.num_dof, dtype=torch.float, device=self.device)
for index, dof_name in enumerate(self.articulations.dof_names):
# dof pos
for re_key, value in self.cfg.init_state.dof_pos.items():
if re.match(re_key, dof_name):
self._default_dof_pos[:, index] = value
self._data.default_dof_pos[:, index] = value
# dof vel
for re_key, value in self.cfg.init_state.dof_vel.items():
if re.match(re_key, dof_name):
self._default_dof_vel[:, index] = value
self._data.default_dof_vel[:, index] = value
# -- tracked sites
if self.cfg.meta_info.sites_names:
sites_names = list()
......
......@@ -46,6 +46,12 @@ class ArticulatedObjectData:
dof_acc: torch.Tensor = None
"""DOF acceleration of all joints. Shape is ``(count, num_dof)``."""
default_dof_pos: torch.Tensor = None
"""DOF default positions of all joints. Shape is ``(count, num_dof)``."""
default_dof_vel: torch.Tensor = None
"""DOF default velocities of all joints. Shape is ``(count, num_dof)``."""
"""
Properties
"""
......
......@@ -18,8 +18,8 @@ Reference:
import math
from scipy.spatial.transform import Rotation
from omni.isaac.orbit.actuators.config.anydrive import ANYMAL_C_DEFAULT_GROUP_CFG
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
from omni.isaac.orbit.actuators.config.anydrive import Anydrive3LSTMCfg
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, ISAAC_ORBIT_NUCLEUS_DIR
from ..legged_robot import LeggedRobotCfg
......@@ -47,31 +47,28 @@ def euler_rpy_apply(rpy, xyz, degrees=False):
##
_ANYMAL_B_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmalB/anymal_b_instanceable.usd"
_ANYMAL_C_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmalC/anymal_c_minimal_instanceable.usd"
# _ANYMAL_C_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmalC/anymal_c_minimal_instanceable.usd"
_ANYMAL_C_INSTANCEABLE_USD = f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.usd"
ANYMAL_B_CFG = LeggedRobotCfg(
meta_info=LeggedRobotCfg.MetaInfoCfg(usd_path=_ANYMAL_B_INSTANCEABLE_USD, soft_dof_pos_limit_factor=0.95),
feet_info={
"LF_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="LF_SHANK",
"LF_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=(0.1, -0.02, -0.3215),
),
"RF_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="RF_SHANK",
"RF_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=(0.1, 0.02, -0.3215),
),
"LH_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="LH_SHANK",
"LH_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=(-0.1, -0.02, -0.3215),
),
"RH_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="RH_SHANK",
"RH_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=(-0.1, 0.02, -0.3215),
),
},
init_state=LeggedRobotCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.6),
pos=(0.0, 0.0, 0.62),
dof_pos={
".*HAA": 0.0, # all HAA
".*F_HFE": 0.4, # both front HFE
......@@ -95,32 +92,28 @@ ANYMAL_B_CFG = LeggedRobotCfg(
rest_offset=0.0,
),
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0
),
actuator_groups={"base_legs": ANYMAL_C_DEFAULT_GROUP_CFG},
actuators={"legs": Anydrive3LSTMCfg(dof_name_expr=[".*HAA", ".*HFE", ".*KFE"])},
)
"""Configuration of ANYmal-B robot using actuator-net."""
ANYMAL_C_CFG = LeggedRobotCfg(
meta_info=LeggedRobotCfg.MetaInfoCfg(usd_path=_ANYMAL_C_INSTANCEABLE_USD, soft_dof_pos_limit_factor=0.95),
feet_info={
"LF_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="LF_SHANK",
"LF_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=euler_rpy_apply(rpy=(0, 0, -math.pi / 2), xyz=(0.08795, 0.01305, -0.33797)),
rot_offset=quat_from_euler_rpy(0, 0, -math.pi / 2),
),
"RF_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="RF_SHANK",
"RF_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=euler_rpy_apply(rpy=(0, 0, math.pi / 2), xyz=(0.08795, -0.01305, -0.33797)),
rot_offset=quat_from_euler_rpy(0, 0, math.pi / 2),
),
"LH_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="LH_SHANK",
"LH_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=euler_rpy_apply(rpy=(0, 0, -math.pi / 2), xyz=(-0.08795, 0.01305, -0.33797)),
rot_offset=quat_from_euler_rpy(0, 0, -math.pi / 2),
),
"RH_FOOT": LeggedRobotCfg.FootFrameCfg(
body_name="RH_SHANK",
"RH_SHANK": LeggedRobotCfg.FootFrameCfg(
pos_offset=euler_rpy_apply(rpy=(0, 0, math.pi / 2), xyz=(-0.08795, -0.01305, -0.33797)),
rot_offset=quat_from_euler_rpy(0, 0, math.pi / 2),
),
......@@ -152,6 +145,6 @@ ANYMAL_C_CFG = LeggedRobotCfg(
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
actuator_groups={"base_legs": ANYMAL_C_DEFAULT_GROUP_CFG},
actuators={"legs": Anydrive3LSTMCfg(dof_name_expr=[".*HAA", ".*HFE", ".*KFE"])},
)
"""Configuration of ANYmal-C robot using actuator-net."""
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
# # Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# # All rights reserved.
# #
# # SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the Franka Emika robots.
# """Configuration for the Franka Emika robots.
The following configurations are available:
# The following configurations are available:
* :obj:`FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG`: Franka Emika Panda robot with Panda hand
# * :obj:`FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG`: Franka Emika Panda robot with Panda hand
Reference: https://github.com/frankaemika/franka_ros
"""
# Reference: https://github.com/frankaemika/franka_ros
# """
from omni.isaac.orbit.actuators.config.franka import PANDA_HAND_MIMIC_GROUP_CFG
from omni.isaac.orbit.actuators.group import ActuatorGroupCfg
from omni.isaac.orbit.actuators.group.actuator_group_cfg import ActuatorControlCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
# from omni.isaac.orbit.actuators.config.franka import PANDA_HAND_MIMIC_GROUP_CFG
# from omni.isaac.orbit.actuators.group import ActuatorGroupCfg
# from omni.isaac.orbit.actuators.group.actuator_group_cfg import ActuatorControlCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
from ..single_arm import SingleArmManipulatorCfg
# from ..single_arm import SingleArmManipulatorCfg
_FRANKA_PANDA_ARM_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/FrankaEmika/panda_instanceable.usd"
# _FRANKA_PANDA_ARM_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/FrankaEmika/panda_instanceable.usd"
FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG = SingleArmManipulatorCfg(
meta_info=SingleArmManipulatorCfg.MetaInfoCfg(
usd_path=_FRANKA_PANDA_ARM_INSTANCEABLE_USD,
arm_num_dof=7,
tool_num_dof=2,
tool_sites_names=["panda_leftfinger", "panda_rightfinger"],
),
init_state=SingleArmManipulatorCfg.InitialStateCfg(
dof_pos={
"panda_joint1": 0.0,
"panda_joint2": -0.569,
"panda_joint3": 0.0,
"panda_joint4": -2.810,
"panda_joint5": 0.0,
"panda_joint6": 3.037,
"panda_joint7": 0.741,
"panda_finger_joint*": 0.04,
},
dof_vel={".*": 0.0},
),
ee_info=SingleArmManipulatorCfg.EndEffectorFrameCfg(
body_name="panda_hand", pos_offset=(0.0, 0.0, 0.1034), rot_offset=(1.0, 0.0, 0.0, 0.0)
),
rigid_props=SingleArmManipulatorCfg.RigidBodyPropertiesCfg(
max_depenetration_velocity=5.0,
),
collision_props=SingleArmManipulatorCfg.CollisionPropertiesCfg(
contact_offset=0.005,
rest_offset=0.0,
),
articulation_props=SingleArmManipulatorCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True,
),
actuator_groups={
"panda_shoulder": ActuatorGroupCfg(
dof_names=["panda_joint[1-4]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": 800.0},
damping={".*": 40.0},
dof_pos_offset={
"panda_joint1": 0.0,
"panda_joint2": -0.569,
"panda_joint3": 0.0,
"panda_joint4": -2.810,
},
),
),
"panda_forearm": ActuatorGroupCfg(
dof_names=["panda_joint[5-7]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=12.0),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": 800.0},
damping={".*": 40.0},
dof_pos_offset={"panda_joint5": 0.0, "panda_joint6": 3.037, "panda_joint7": 0.741},
),
),
"panda_hand": PANDA_HAND_MIMIC_GROUP_CFG,
},
)
"""Configuration of Franka arm with Franka Hand using implicit actuator models."""
# FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG = SingleArmManipulatorCfg(
# meta_info=SingleArmManipulatorCfg.MetaInfoCfg(
# usd_path=_FRANKA_PANDA_ARM_INSTANCEABLE_USD,
# arm_num_dof=7,
# tool_num_dof=2,
# tool_sites_names=["panda_leftfinger", "panda_rightfinger"],
# ),
# init_state=SingleArmManipulatorCfg.InitialStateCfg(
# dof_pos={
# "panda_joint1": 0.0,
# "panda_joint2": -0.569,
# "panda_joint3": 0.0,
# "panda_joint4": -2.810,
# "panda_joint5": 0.0,
# "panda_joint6": 3.037,
# "panda_joint7": 0.741,
# "panda_finger_joint*": 0.04,
# },
# dof_vel={".*": 0.0},
# ),
# ee_info=SingleArmManipulatorCfg.EndEffectorFrameCfg(
# body_name="panda_hand", pos_offset=(0.0, 0.0, 0.1034), rot_offset=(1.0, 0.0, 0.0, 0.0)
# ),
# rigid_props=SingleArmManipulatorCfg.RigidBodyPropertiesCfg(
# max_depenetration_velocity=5.0,
# ),
# collision_props=SingleArmManipulatorCfg.CollisionPropertiesCfg(
# contact_offset=0.005,
# rest_offset=0.0,
# ),
# articulation_props=SingleArmManipulatorCfg.ArticulationRootPropertiesCfg(
# enable_self_collisions=True,
# ),
# actuator_groups={
# "panda_shoulder": ActuatorGroupCfg(
# dof_names=["panda_joint[1-4]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": 800.0},
# damping={".*": 40.0},
# ),
# dof_pos_offset={
# "panda_joint1": 0.0,
# "panda_joint2": -0.569,
# "panda_joint3": 0.0,
# "panda_joint4": -2.810,
# },
# ),
# "panda_forearm": ActuatorGroupCfg(
# dof_names=["panda_joint[5-7]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=12.0),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": 800.0},
# damping={".*": 40.0},
# dof_pos_offset={"panda_joint5": 0.0, "panda_joint6": 3.037, "panda_joint7": 0.741},
# ),
# ),
# "panda_hand": PANDA_HAND_MIMIC_GROUP_CFG,
# },
# )
# """Configuration of Franka arm with Franka Hand using implicit actuator models."""
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
# # Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# # All rights reserved.
# #
# # SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the Ridgeback-Manipulation robots.
# """Configuration for the Ridgeback-Manipulation robots.
The following configurations are available:
# The following configurations are available:
* :obj:`RIDGEBACK_FRANKA_PANDA_CFG`: Clearpath Ridgeback base with Franka Emika arm
# * :obj:`RIDGEBACK_FRANKA_PANDA_CFG`: Clearpath Ridgeback base with Franka Emika arm
Reference: https://github.com/ridgeback/ridgeback_manipulation
"""
# Reference: https://github.com/ridgeback/ridgeback_manipulation
# """
from omni.isaac.orbit.actuators.config.franka import PANDA_HAND_MIMIC_GROUP_CFG
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, ActuatorGroupCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
# from omni.isaac.orbit.actuators.config.franka import PANDA_HAND_MIMIC_GROUP_CFG
# from omni.isaac.orbit.actuators.group import ActuatorControlCfg, ActuatorGroupCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from ..mobile_manipulator import MobileManipulatorCfg
# from ..mobile_manipulator import MobileManipulatorCfg
_RIDGEBACK_FRANKA_PANDA_ARM_USD = f"{ISAAC_NUCLEUS_DIR}/Robots/Clearpath/RidgebackFranka/ridgeback_franka.usd"
# _RIDGEBACK_FRANKA_PANDA_ARM_USD = f"{ISAAC_NUCLEUS_DIR}/Robots/Clearpath/RidgebackFranka/ridgeback_franka.usd"
RIDGEBACK_FRANKA_PANDA_CFG = MobileManipulatorCfg(
meta_info=MobileManipulatorCfg.MetaInfoCfg(
usd_path=_RIDGEBACK_FRANKA_PANDA_ARM_USD,
base_num_dof=3,
arm_num_dof=7,
tool_num_dof=2,
tool_sites_names=["panda_leftfinger", "panda_rightfinger"],
),
init_state=MobileManipulatorCfg.InitialStateCfg(
dof_pos={
# base
"dummy_base_prismatic_y_joint": 0.0,
"dummy_base_prismatic_x_joint": 0.0,
"dummy_base_revolute_z_joint": 0.0,
# franka arm
"panda_joint1": 0.0,
"panda_joint2": -0.569,
"panda_joint3": 0.0,
"panda_joint4": -2.810,
"panda_joint5": 0.0,
"panda_joint6": 3.037,
"panda_joint7": 0.741,
# tool
"panda_finger_joint*": 0.035,
},
dof_vel={".*": 0.0},
),
ee_info=MobileManipulatorCfg.EndEffectorFrameCfg(
body_name="panda_hand", pos_offset=(0.0, 0.0, 0.1034), rot_offset=(1.0, 0.0, 0.0, 0.0)
),
actuator_groups={
"base": ActuatorGroupCfg(
dof_names=["dummy_base_.*"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=1000.0),
control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 0.0}, damping={".*": 1e5}),
),
"panda_shoulder": ActuatorGroupCfg(
dof_names=["panda_joint[1-4]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": 800.0},
damping={".*": 40.0},
dof_pos_offset={
"panda_joint1": 0.0,
"panda_joint2": -0.569,
"panda_joint3": 0.0,
"panda_joint4": -2.810,
},
),
),
"panda_forearm": ActuatorGroupCfg(
dof_names=["panda_joint[5-7]"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=12.0),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": 800.0},
damping={".*": 40.0},
dof_pos_offset={"panda_joint5": 0.0, "panda_joint6": 3.037, "panda_joint7": 0.741},
),
),
"panda_hand": PANDA_HAND_MIMIC_GROUP_CFG,
},
)
"""Configuration of Franka arm with Franka Hand on a Clearpath Ridgeback base using implicit actuator models.
# RIDGEBACK_FRANKA_PANDA_CFG = MobileManipulatorCfg(
# meta_info=MobileManipulatorCfg.MetaInfoCfg(
# usd_path=_RIDGEBACK_FRANKA_PANDA_ARM_USD,
# base_num_dof=3,
# arm_num_dof=7,
# tool_num_dof=2,
# tool_sites_names=["panda_leftfinger", "panda_rightfinger"],
# ),
# init_state=MobileManipulatorCfg.InitialStateCfg(
# dof_pos={
# # base
# "dummy_base_prismatic_y_joint": 0.0,
# "dummy_base_prismatic_x_joint": 0.0,
# "dummy_base_revolute_z_joint": 0.0,
# # franka arm
# "panda_joint1": 0.0,
# "panda_joint2": -0.569,
# "panda_joint3": 0.0,
# "panda_joint4": -2.810,
# "panda_joint5": 0.0,
# "panda_joint6": 3.037,
# "panda_joint7": 0.741,
# # tool
# "panda_finger_joint*": 0.035,
# },
# dof_vel={".*": 0.0},
# ),
# ee_info=MobileManipulatorCfg.EndEffectorFrameCfg(
# body_name="panda_hand", pos_offset=(0.0, 0.0, 0.1034), rot_offset=(1.0, 0.0, 0.0, 0.0)
# ),
# actuator_groups={
# "base": ActuatorGroupCfg(
# dof_names=["dummy_base_.*"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=1000.0),
# control_cfg=ActuatorControlCfg(command_types=["v_abs"], stiffness={".*": 0.0}, damping={".*": 1e5}),
# ),
# "panda_shoulder": ActuatorGroupCfg(
# dof_names=["panda_joint[1-4]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": 800.0},
# damping={".*": 40.0},
# dof_pos_offset={
# "panda_joint1": 0.0,
# "panda_joint2": -0.569,
# "panda_joint3": 0.0,
# "panda_joint4": -2.810,
# },
# ),
# ),
# "panda_forearm": ActuatorGroupCfg(
# dof_names=["panda_joint[5-7]"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=12.0),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": 800.0},
# damping={".*": 40.0},
# dof_pos_offset={"panda_joint5": 0.0, "panda_joint6": 3.037, "panda_joint7": 0.741},
# ),
# ),
# "panda_hand": PANDA_HAND_MIMIC_GROUP_CFG,
# },
# )
# """Configuration of Franka arm with Franka Hand on a Clearpath Ridgeback base using implicit actuator models.
The following control configuration is used:
# The following control configuration is used:
* Base: velocity control with damping
* Arm: position control with damping (contains default position offsets)
* Hand: mimic control
# * Base: velocity control with damping
# * Arm: position control with damping (contains default position offsets)
# * Hand: mimic control
"""
# """
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
# # Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# # All rights reserved.
# #
# # SPDX-License-Identifier: BSD-3-Clause
"""Configuration for Unitree robots.
# """Configuration for Unitree robots.
The following configurations are available:
# 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 simple PD controller for the legs
Reference: https://github.com/unitreerobotics/unitree_ros
"""
# Reference: https://github.com/unitreerobotics/unitree_ros
# """
from omni.isaac.orbit.actuators.group import ActuatorControlCfg, ActuatorGroupCfg
from omni.isaac.orbit.actuators.model.actuator_cfg import DCMotorCfg
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
# from omni.isaac.orbit.actuators.group import ActuatorControlCfg, ActuatorGroupCfg
# from omni.isaac.orbit.actuators.model.actuator_cfg import DCMotorCfg
# from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
from ..legged_robot import LeggedRobotCfg
# from ..legged_robot import LeggedRobotCfg
##
# Configuration
##
# ##
# # Configuration
# ##
_UNITREE_A1_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/Unitree/A1/a1_instanceable.usd"
# _UNITREE_A1_INSTANCEABLE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/Unitree/A1/a1_instanceable.usd"
UNITREE_A1_CFG = LeggedRobotCfg(
meta_info=LeggedRobotCfg.MetaInfoCfg(usd_path=_UNITREE_A1_INSTANCEABLE_USD, soft_dof_pos_limit_factor=0.9),
feet_info={
"FR_foot": LeggedRobotCfg.FootFrameCfg(body_name="FR_calf", pos_offset=(0.0, 0.0, -0.2)),
"FL_foot": LeggedRobotCfg.FootFrameCfg(body_name="FL_calf", pos_offset=(0.0, 0.0, -0.2)),
"RR_foot": LeggedRobotCfg.FootFrameCfg(body_name="RR_calf", pos_offset=(0.0, 0.0, -0.2)),
"RL_foot": LeggedRobotCfg.FootFrameCfg(body_name="RL_calf", pos_offset=(0.0, 0.0, -0.2)),
},
init_state=LeggedRobotCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.42),
dof_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.8,
},
dof_vel={".*": 0.0},
),
rigid_props=LeggedRobotCfg.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,
),
collision_props=LeggedRobotCfg.CollisionPropertiesCfg(
contact_offset=0.02,
rest_offset=0.0,
),
articulation_props=LeggedRobotCfg.ArticulationRootPropertiesCfg(
enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
),
actuator_groups={
"base_legs": ActuatorGroupCfg(
dof_names=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
model_cfg=DCMotorCfg(
motor_torque_limit=33.5, gear_ratio=1.0, peak_motor_torque=33.5, motor_velocity_limit=21.0
),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": 25.0},
damping={".*": 0.5},
dof_pos_offset={
".*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.8,
},
),
)
},
)
"""Configuration of Unitree A1 using DC motor.
# UNITREE_A1_CFG = LeggedRobotCfg(
# meta_info=LeggedRobotCfg.MetaInfoCfg(usd_path=_UNITREE_A1_INSTANCEABLE_USD, soft_dof_pos_limit_factor=0.9),
# feet_info={
# "FR_foot": LeggedRobotCfg.FootFrameCfg(body_name="FR_calf", pos_offset=(0.0, 0.0, -0.2)),
# "FL_foot": LeggedRobotCfg.FootFrameCfg(body_name="FL_calf", pos_offset=(0.0, 0.0, -0.2)),
# "RR_foot": LeggedRobotCfg.FootFrameCfg(body_name="RR_calf", pos_offset=(0.0, 0.0, -0.2)),
# "RL_foot": LeggedRobotCfg.FootFrameCfg(body_name="RL_calf", pos_offset=(0.0, 0.0, -0.2)),
# },
# init_state=LeggedRobotCfg.InitialStateCfg(
# pos=(0.0, 0.0, 0.42),
# dof_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.8,
# },
# dof_vel={".*": 0.0},
# ),
# rigid_props=LeggedRobotCfg.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=LeggedRobotCfg.ArticulationRootPropertiesCfg(
# enable_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=1
# ),
# actuator_groups={
# "base_legs": ActuatorGroupCfg(
# dof_names=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
# model_cfg=DCMotorCfg(
# motor_torque_limit=33.5, gear_ratio=1.0, peak_motor_torque=33.5, motor_velocity_limit=21.0
# ),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": 25.0},
# damping={".*": 0.5},
# dof_pos_offset={
# ".*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.8,
# },
# ),
# )
# },
# )
# """Configuration of Unitree A1 using DC motor.
Note: Specifications taken from: https://www.trossenrobotics.com/a1-quadruped#specifications
"""
# Note: Specifications taken from: https://www.trossenrobotics.com/a1-quadruped#specifications
# """
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the Universal Robots.
The following configuration parameters are available:
* :obj:`UR10_CFG`: The UR10 arm without a gripper.
Reference: https://github.com/ros-industrial/universal_robot
"""
from omni.isaac.orbit.actuators.group import ActuatorGroupCfg
from omni.isaac.orbit.actuators.group.actuator_group_cfg import ActuatorControlCfg
from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
from ..single_arm import SingleArmManipulatorCfg
_UR10_ARM_INSTANCEBALE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/UniversalRobots/UR10/ur10_instanceable.usd"
UR10_CFG = SingleArmManipulatorCfg(
meta_info=SingleArmManipulatorCfg.MetaInfoCfg(
usd_path=_UR10_ARM_INSTANCEBALE_USD,
arm_num_dof=6,
tool_num_dof=0,
tool_sites_names=None,
),
init_state=SingleArmManipulatorCfg.InitialStateCfg(
dof_pos={
"shoulder_pan_joint": 0.0,
"shoulder_lift_joint": -1.712,
"elbow_joint": 1.712,
"wrist_1_joint": 0.0,
"wrist_2_joint": 0.0,
"wrist_3_joint": 0.0,
},
dof_vel={".*": 0.0},
),
ee_info=SingleArmManipulatorCfg.EndEffectorFrameCfg(body_name="ee_link"),
actuator_groups={
"arm": ActuatorGroupCfg(
dof_names=[".*"],
model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
control_cfg=ActuatorControlCfg(
command_types=["p_abs"],
stiffness={".*": None},
damping={".*": None},
),
),
},
)
"""Configuration of UR-10 arm using implicit actuator models."""
# # Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# # All rights reserved.
# #
# # SPDX-License-Identifier: BSD-3-Clause
# """Configuration for the Universal Robots.
# The following configuration parameters are available:
# * :obj:`UR10_CFG`: The UR10 arm without a gripper.
# Reference: https://github.com/ros-industrial/universal_robot
# """
# from omni.isaac.orbit.actuators.group import ActuatorGroupCfg
# from omni.isaac.orbit.actuators.group.actuator_group_cfg import ActuatorControlCfg
# from omni.isaac.orbit.actuators.model import ImplicitActuatorCfg
# from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
# from ..single_arm import SingleArmManipulatorCfg
# _UR10_ARM_INSTANCEBALE_USD = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/UniversalRobots/UR10/ur10_instanceable.usd"
# UR10_CFG = SingleArmManipulatorCfg(
# meta_info=SingleArmManipulatorCfg.MetaInfoCfg(
# usd_path=_UR10_ARM_INSTANCEBALE_USD,
# arm_num_dof=6,
# tool_num_dof=0,
# tool_sites_names=None,
# ),
# init_state=SingleArmManipulatorCfg.InitialStateCfg(
# dof_pos={
# "shoulder_pan_joint": 0.0,
# "shoulder_lift_joint": -1.712,
# "elbow_joint": 1.712,
# "wrist_1_joint": 0.0,
# "wrist_2_joint": 0.0,
# "wrist_3_joint": 0.0,
# },
# dof_vel={".*": 0.0},
# ),
# ee_info=SingleArmManipulatorCfg.EndEffectorFrameCfg(body_name="wrist_3_link"),
# actuator_groups={
# "arm": ActuatorGroupCfg(
# dof_names=[".*"],
# model_cfg=ImplicitActuatorCfg(velocity_limit=100.0, torque_limit=87.0),
# control_cfg=ActuatorControlCfg(
# command_types=["p_abs"],
# stiffness={".*": None},
# damping={".*": None},
# ),
# ),
# },
# )
# """Configuration of UR-10 arm using implicit actuator models."""
......@@ -4,7 +4,7 @@
# SPDX-License-Identifier: BSD-3-Clause
from dataclasses import MISSING
from typing import Dict, Optional, Tuple
from typing import Dict, Tuple
from omni.isaac.orbit.utils import configclass
......@@ -26,24 +26,6 @@ class LeggedRobotCfg(RobotBaseCfg):
rot_offset: Tuple[float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""Additional rotation offset (w, x, y, z) from the body frame. (default: (1, 0, 0, 0)."""
@configclass
class PhysicsMaterialCfg:
"""Physics material applied to the feet of the robot."""
prim_path = "/World/Materials/footMaterial"
"""Path to the physics material prim. Defaults to /World/Materials/footMaterial.
Note:
If the prim path is not absolute, it will be resolved relative to the path specified when spawning
the object.
"""
static_friction: float = 1.0
"""Static friction coefficient. Defaults to 1.0."""
dynamic_friction: float = 1.0
"""Dynamic friction coefficient. Defaults to 1.0."""
restitution: float = 0.0
"""Restitution coefficient. Defaults to 0.0."""
##
# Initialize configurations.
##
......@@ -53,8 +35,3 @@ class LeggedRobotCfg(RobotBaseCfg):
The returned tensor for feet state is in the same order as that of the provided list.
"""
physics_material: Optional[PhysicsMaterialCfg] = PhysicsMaterialCfg()
"""Settings for the physics material to apply to feet.
If set to None, no physics material will be created and applied.
"""
......@@ -26,18 +26,8 @@ class LeggedRobotData(RobotBaseData):
feet_state_w: torch.Tensor = None
"""Feet sites frames state `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is ``(count, num_feet, 13)``."""
feet_state_b: torch.Tensor = None
"""Feet frames state `[pos, quat, lin_vel, ang_vel]` in base frame. Shape is ``(count, num_feet, 13)``."""
feet_air_time: torch.Tensor = None
"""Time spent (in s) during swing phase of each leg since last contact. Shape is ``(count, num_feet)``."""
##
# Proprioceptive sensors.
##
feet_contact_forces: torch.Tensor = None
"""Feet contact wrenches `[force, torque]` in simulation world frame. Shape is ``(count, num_feet, 6)``."""
feet_pose_b: torch.Tensor = None
"""Feet frames pose `[pos, quat]` in base frame. Shape is ``(count, num_feet, 13)``."""
"""
Properties
......@@ -52,3 +42,33 @@ class LeggedRobotData(RobotBaseData):
def root_ang_vel_b(self) -> torch.Tensor:
"""Root angular velocity in simulation world frame. Shape is ``(count, 3)``."""
return self.root_vel_b[:, 3:6]
@property
def feet_pos_w(self) -> torch.Tensor:
"""Feet position in simulation world frame. Shape is ``(count, num_feet, 3)``."""
return self.feet_state_w[..., :3]
@property
def feet_quat_w(self) -> torch.Tensor:
"""Feet orientation (w, x, y, z) in simulation world frame. Shape is ``(count, num_feet, 4)``."""
return self.feet_state_w[:, 3:7]
@property
def feet_lin_vel_w(self) -> torch.Tensor:
"""Feet linear velocity in simulation world frame. Shape is ``(count, num_feet, 3)``."""
return self.feet_state_w[:, 7:10]
@property
def feet_ang_vel_w(self) -> torch.Tensor:
"""Feet angular velocity in simulation world frame. Shape is ``(count, num_feet, 3)``."""
return self.feet_state_w[:, 10:13]
@property
def feet_pos_b(self) -> torch.Tensor:
"""Feet position in base frame. Shape is ``(count, num_feet, 3)``."""
return self.feet_pose_b[..., :3]
@property
def feet_quat_b(self) -> torch.Tensor:
"""Feet orientation (w, x, y, z) in base world frame. Shape is ``(count, num_feet, 4)``."""
return self.feet_pose_b[:, 3:7]
......@@ -6,7 +6,7 @@
from dataclasses import MISSING
from typing import Dict, Optional, Tuple
from omni.isaac.orbit.actuators.group import ActuatorGroupCfg
from omni.isaac.orbit.actuators import ActuatorBaseCfg
from omni.isaac.orbit.utils import configclass
......@@ -34,7 +34,7 @@ class RobotBaseCfg:
"""Angular damping coefficient."""
max_linear_velocity: Optional[float] = 1000.0
"""Maximum linear velocity for rigid bodies (in m/s). Defaults to 1000.0."""
max_angular_velocity: Optional[float] = 1000.0
max_angular_velocity: Optional[float] = 64.0
"""Maximum angular velocity for rigid bodies (in rad/s). Defaults to 1000.0."""
max_depenetration_velocity: Optional[float] = 10.0
"""Maximum depenetration velocity permitted to be introduced by the solver (in m/s).
......@@ -43,6 +43,8 @@ class RobotBaseCfg:
"""Disable gravity for the actor. Defaults to False."""
retain_accelerations: Optional[bool] = None
"""Carries over forces/accelerations over sub-steps."""
sleep_threshold: Optional[float] = 0.0
"""Sleep threshold for the body. Defaults to 0.0."""
@configclass
class CollisionPropertiesCfg:
......@@ -69,6 +71,8 @@ class RobotBaseCfg:
"""Solver position iteration counts for the body."""
solver_velocity_iteration_count: Optional[int] = None
"""Solver position iteration counts for the body."""
sleep_threshold: Optional[float] = 0.0
"""Sleep threshold for the body. Defaults to 0.0."""
@configclass
class InitialStateCfg:
......@@ -91,6 +95,24 @@ class RobotBaseCfg:
dof_vel: Dict[str, float] = MISSING
"""DOF velocities of all joints."""
@configclass
class PhysicsMaterialCfg:
"""Physics material applied to the feet of the robot."""
prim_path = "/World/Materials/RobotPhysicsMaterial"
"""Path to the physics material prim. Defaults to /World/Materials/RobotPhysicsMaterial.
Note:
If the prim path is not absolute, it will be resolved relative to the path specified when spawning
the object.
"""
static_friction: float = 1.0
"""Static friction coefficient. Defaults to 1.0."""
dynamic_friction: float = 1.0
"""Dynamic friction coefficient. Defaults to 1.0."""
restitution: float = 0.0
"""Restitution coefficient. Defaults to 0.0."""
##
# Initialize configurations.
##
......@@ -105,5 +127,10 @@ class RobotBaseCfg:
"""Properties to apply to all collisions in the articulation."""
articulation_props: ArticulationRootPropertiesCfg = ArticulationRootPropertiesCfg()
"""Properties to apply to articulation."""
actuator_groups: Dict[str, ActuatorGroupCfg] = MISSING
"""Actuator groups for the robot."""
actuators: Dict[str, ActuatorBaseCfg] = MISSING
"""Actuators for the robot with corresponding dof names."""
physics_material: Optional[PhysicsMaterialCfg] = PhysicsMaterialCfg()
"""Settings for the physics material to apply to feet.
If set to None, no physics material will be created and applied.
"""
debug_vis: bool = False
......@@ -5,12 +5,20 @@
import torch
from dataclasses import dataclass
from typing import List
@dataclass
class RobotBaseData:
"""Data container for a robot."""
##
# Properties.
##
dof_names: List[str] = None
"""DOF names in the order parsed by the simulation view."""
##
# Frame states.
##
......@@ -18,6 +26,9 @@ class RobotBaseData:
root_state_w: torch.Tensor = None
"""Root state `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is ``(count, 13)``."""
body_state_w: torch.Tensor = None
"""State of all bodies `[pos, quat, lin_vel, ang_vel]` in simulation world frame. Shape is ``(count, num_bodies, 13)``."""
##
# DOF states <- From simulation.
##
......@@ -31,6 +42,12 @@ class RobotBaseData:
dof_acc: torch.Tensor = None
"""DOF acceleration of all joints. Shape is ``(count, num_dof)``."""
default_dof_pos: torch.Tensor = None
"""DOF default positions of all joints. Shape is ``(count, num_dof)``."""
default_dof_vel: torch.Tensor = None
"""DOF default velocities of all joints. Shape is ``(count, num_dof)``."""
##
# DOF commands -- Set into simulation.
##
......@@ -53,6 +70,12 @@ class RobotBaseData:
Note: The torques are zero for implicit actuator models without feed-forward torque.
"""
dof_stiffness: torch.Tensor = None
"""DOF stiffness provided to simulation. Shape is ``(count, num_dof)``."""
dof_damping: torch.Tensor = None
"""DOF damping provided to simulation. Shape is ``(count, num_dof)``."""
##
# DOF commands -- Explicit actuators.
##
......@@ -71,13 +94,6 @@ class RobotBaseData:
Note: The torques are zero for implicit actuator models.
"""
##
# Default actuator offsets <- From the actuator groups.
##
actuator_pos_offset: torch.Tensor = None
"""Joint positions offsets applied by actuators when using "p_abs". Shape is ``(count, num_dof)``."""
##
# Other Data.
##
......
......@@ -15,3 +15,4 @@ from .camera import * # noqa: F401, F403
from .contact_sensor import * # noqa: F401, F403
from .ray_caster import * # noqa: F401, F403
from .sensor_base import SensorBase # noqa: F401
from .sensor_base_cfg import SensorBaseCfg # noqa: F401
......@@ -54,6 +54,8 @@ class PinholeCameraCfg(SensorBaseCfg):
vertical_aperture_offset: float = None
"""Offsets Resolution/Film gate vertically."""
cls_name = "Camera"
data_types: List[str] = ["rgb"]
"""List of sensor names/types to enable for the camera. Defaults to ["rgb"]."""
width: int = MISSING
......
......@@ -17,6 +17,8 @@ from ..sensor_base_cfg import SensorBaseCfg
class ContactSensorCfg(SensorBaseCfg):
"""Configuration for the contact sensor."""
cls_name = "ContactSensor"
filter_prim_paths_expr: list[str] = list()
"""The list of primitive paths to filter contacts with.
......@@ -27,3 +29,7 @@ class ContactSensorCfg(SensorBaseCfg):
If an empty list is provided, then only net contact forces are reported.
"""
history_length: int = 0
"""Number of past frames to store in the sensor buffers. Defaults to 0, which means that only
the current data is stored."""
......@@ -21,11 +21,21 @@ class ContactSensorData:
Shape is (N, 4), where ``N`` is the number of sensors.
"""
net_forces_w: torch.Tensor = None
"""The net contact forces in world frame.
Shape is (N, B, 3), where ``N`` is the number of sensors and ``B`` is the number of bodies in each sensor.
"""
net_forces_w_history: torch.Tensor = None
"""The net contact forces in world frame.
Shape is (N, T, B, 3), where ``N`` is the number of sensors, ``T`` is the configured history length
and ``B`` is the number of bodies in each sensor.
In the history dimension, the first index is the most recent and the last index is the oldest.
"""
force_matrix_w: torch.Tensor = None
"""The contact forces filtered between the sensor bodies and filtered bodies in world frame.
......
......@@ -57,46 +57,31 @@ class RayCaster(SensorBase):
self._data = RayCasterData()
# List of meshes to ray-cast
self.warp_meshes = []
# visualization markers
self.ray_visualizer = None
def __str__(self) -> str:
"""Returns: A string containing information about the instance."""
return (
f"Ray-caster @ '{self._view._regex_prim_paths}': \n"
f"\tview type : {self._view.__class__}\n"
f"\tupdate period (s) : {self._update_period}\n"
f"\tupdate period (s) : {self.cfg.update_period}\n"
f"\tnumber of meshes : {len(self.warp_meshes)}\n"
f"\tnumber of sensors: {self.view.count}\n"
f"\tnumber of sensors: {self._view.count}\n"
f"\tnumber of rays/sensor : {self.num_rays}\n"
f"\ttotal number of rays : {self.num_rays * self.view.count}"
f"\ttotal number of rays : {self.num_rays * self._view.count}"
)
"""
Properties
"""
@property
def data(self) -> RayCasterData:
"""Data related to ray-caster."""
return self._data
"""
Operations
"""
def spawn(self, prim_path: str, *args, **kwargs):
"""Spawns the sensor in the scene.
Note:
Ray-caster is a virtual sensor and does not need to be spawned. However,
this function is required by the base class.
"""
pass
def initialize(self, prim_paths_expr: str):
def initialize(self, env_prim_path: str):
# check if the prim at path is a articulated or rigid prim
# we do this since for physics-based view classes we can access their data directly
# otherwise we need to use the xform view class which is slower
prim_view_class = None
prim_paths_expr = f"{env_prim_path}/{self.cfg.prim_path_expr}"
for prim_path in prim_utils.find_matching_prim_paths(prim_paths_expr):
# get prim at path
prim = prim_utils.get_prim_at_path(prim_path)
......@@ -117,10 +102,7 @@ class RayCaster(SensorBase):
self._view = prim_view_class(prim_paths_expr, reset_xform_properties=False)
self._view.initialize()
# initialize the base class
super().initialize(prim_paths_expr)
# Check that backend is compatible
if self._backend != "torch":
raise RuntimeError(f"RayCaster only supports PyTorch backend. Received: {self._backend}.")
super().initialize(env_prim_path)
# check number of mesh prims provided
if len(self.cfg.mesh_prim_paths) != 1:
......@@ -165,24 +147,12 @@ class RayCaster(SensorBase):
self._data.quat_w = torch.zeros(self._view.count, 4, device=self._device)
self._data.ray_hits_w = torch.zeros(self._view.count, self.num_rays, 3, device=self._device)
# visualization of the ray-caster
prim_path = stage_utils.get_next_free_path("/Visuals/RayCaster")
self.ray_visualizer = VisualizationMarkers(prim_path, cfg=RAY_CASTER_MARKER_CFG)
def reset_buffers(self, env_ids: Sequence[int] | None = None):
"""Resets the sensor internals.
Args:
env_ids (Sequence[int], optional): The sensor ids to reset. Defaults to None.
"""
# reset the timers and counters
super().reset_buffers(env_ids)
# force buffer the data -> needed for reset observations
self._buffer(env_ids)
def debug_vis(self):
# visualize the point hits
if self.cfg.debug_vis:
if self.ray_visualizer is None:
prim_path = stage_utils.get_next_free_path("/Visuals/RayCaster")
self.ray_visualizer = VisualizationMarkers(prim_path, cfg=RAY_CASTER_MARKER_CFG)
# check if prim is visualized
self.ray_visualizer.visualize(self._data.ray_hits_w.view(-1, 3))
......@@ -190,7 +160,7 @@ class RayCaster(SensorBase):
Implementation.
"""
def _buffer(self, env_ids: Sequence[int] | None = None):
def _update_buffers(self, env_ids: Sequence[int] | None = None):
"""Fills the buffers of the sensor data."""
# default to all sensors
if env_ids is None:
......
......@@ -20,6 +20,8 @@ from .patterns_cfg import PatternBaseCfg
class RayCasterCfg(SensorBaseCfg):
"""Configuration for the ray-cast sensor."""
cls_name = "RayCaster"
mesh_prim_paths: list[str] = MISSING
"""The list of mesh primitive paths to ray cast against.
......
......@@ -10,14 +10,13 @@ Each sensor class should inherit from this class and implement the abstract meth
"""
import torch
from abc import ABC, abstractmethod
from typing import Any, List, Optional, Sequence
from omni.isaac.core.prims import XFormPrimView
import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.orbit.utils.array import TensorData
from .sensor_base_cfg import SensorBaseCfg
......@@ -33,32 +32,23 @@ class SensorBase(ABC):
Args:
cfg (SensorBaseCfg): The configuration parameters for the sensor.
"""
# Store the inputs
# Store the config
self.cfg = cfg
# Resolve the sensor update period
self._update_period = 0.0 if cfg.update_freq == 0.0 else 1.0 / cfg.update_freq
# Sensor view -- This can be used to access the underlying XFormPrimView
# Note: This is not initialized here. It is initialized in the derived class.
self._view: XFormPrimView = None
# Current timestamp of animation (in seconds)
self._timestamp: TensorData
# Current timestamp (in seconds)
self._timestamp: torch.Tensor
# Timestamp from last update
self._timestamp_last_update: TensorData
# Frame number when the measurement is taken
self._frame: TensorData
self._timestamp_last_update: torch.Tensor
# ids of envs with outdated data
self._is_outdated: torch.Tensor
# Flag for whether the sensor is initialized
self._is_initialized: bool = False
# data object
self._data: object = None
"""
Properties
"""
@property
def view(self) -> XFormPrimView:
"""The underlying view of the sensor."""
return self._view
@property
def prim_paths(self) -> List[str]:
"""The paths to the sensor prims."""
......@@ -75,39 +65,42 @@ class SensorBase(ABC):
return self._device
@property
def frame(self) -> TensorData:
"""Frame number when the measurement took place."""
return self._frame
@property
def timestamp(self) -> TensorData:
def timestamp(self) -> torch.Tensor:
"""Simulation time of the measurement (in seconds)."""
return self._timestamp
@property
@abstractmethod
def data(self) -> Any:
"""The data from the simulated sensor."""
raise NotImplementedError("The data property is not implemented!")
"""Gets the data from the simulated sensor after updating it if necessary."""
# update sensors if needed
outdated_env_ids = self._is_outdated.nonzero().squeeze(-1)
if len(outdated_env_ids) > 0:
# obtain new data
self._update_buffers(outdated_env_ids)
# update the timestamp from last update
self._timestamp_last_update[outdated_env_ids] = self._timestamp[outdated_env_ids]
# set outdated flag to false for the updated sensors
# TODO (from mayank): Why all of them are false? It is unclear. Shouldn't just be the ones that were updated?
self._is_outdated[:] = False
return self._data
"""
Operations
"""
@abstractmethod
def spawn(self, prim_path: str, *args, **kwargs):
"""Spawns the sensor into the stage.
Args:
prim_path (str): The path of the prim to attach the sensor to.
"""
raise NotImplementedError
pass
def initialize(self, prim_paths_expr: str = None):
def initialize(self, env_prim_path: str = None):
"""Initializes the sensor handles and internal buffers.
Args:
prim_paths_expr (str, optional): The prim path expression for the sensors. Defaults to None.
env_prim_path (str, optional): The (templated) prim path expression to the environments where the sensors are created. Defaults to None.
Raises:
RuntimeError: If the simulation context is not initialized.
......@@ -116,26 +109,18 @@ class SensorBase(ABC):
# Obtain Simulation Context
sim = SimulationContext.instance()
if sim is not None:
self._backend = sim.backend
self._device = sim.device
self._backend_utils = sim.backend_utils
self._sim_physics_dt = sim.get_physics_dt()
else:
raise RuntimeError("Simulation Context is not initialized!")
# Check that view is not None
if self._view is None:
self._view = XFormPrimView(prim_paths_expr, "sensor_view", reset_xform_properties=False)
# Check is prims are found under the given prim path expression
if self._view.count == 0:
raise RuntimeError(f"No prims found for the given prim path expression: {prim_paths_expr}")
# Create constant for the number of sensors
self._ALL_INDICES = self._backend_utils.resolve_indices(None, self.count, device=self.device)
# Current timestamp of animation (in seconds)
self._timestamp = self._backend_utils.create_zeros_tensor((self.count,), "float32", self.device)
# Count number of environments
self._num_envs = len(prim_utils.find_matching_prim_paths(env_prim_path))
# Boolean tensor indicating whether the sensor data has to be refreshed
self._is_outdated = torch.ones(self._num_envs, dtype=torch.bool, device=self._device)
# Current timestamp (in seconds)
self._timestamp = torch.zeros(self._num_envs, device=self._device)
# Timestamp from last update
self._timestamp_last_update = self._backend_utils.create_zeros_tensor((self.count,), "float32", self.device)
# Frame number when the measurement is taken
self._frame = self._backend_utils.create_zeros_tensor((self.count,), "int64", self.device)
self._timestamp_last_update = torch.zeros_like(self._timestamp)
# Set the initialized flag
self._is_initialized = True
......@@ -151,38 +136,20 @@ class SensorBase(ABC):
# Reset the timestamp for the sensors
self._timestamp[env_ids] = 0.0
self._timestamp_last_update[env_ids] = 0.0
# Reset the frame count
self._frame[env_ids] = 0
def update_buffers(self, dt: float):
"""Updates the buffers at sensor frequency.
# Set all reset sensors to outdated so that they are updated when data is called the next time.
self._is_outdated[env_ids] = True
This function performs time-based checks and fills the data into the data container. It
calls the function :meth:`buffer()` to fill the data. The function :meth:`buffer()` should
not be called directly.
Args:
dt (float): The simulation time-step.
"""
def update(self, dt: float, force_recompute: bool = False):
# Update the timestamp for the sensors
self._timestamp += dt
# Check if the sensor is ready to capture
env_ids = self._timestamp - self._timestamp_last_update >= self._update_period
# Get the indices of the sensors that are ready to capture
if self._backend == "torch":
env_ids = env_ids.nonzero(as_tuple=False).squeeze(-1)
elif self._backend == "numpy":
env_ids = env_ids.nonzero()[0]
else:
raise NotImplementedError(f"Backend '{self._backend}' is not supported.")
# Check if any sensor is ready to capture
if len(env_ids) > 0:
# Buffer the data
self._buffer(env_ids)
# Update the frame count
self._frame[env_ids] += 1
# Update capture time
self._timestamp_last_update[env_ids] = self._timestamp[env_ids]
self._is_outdated |= self._timestamp - self._timestamp_last_update + 1e-6 >= self.cfg.update_period
# Update the buffers
# TODO (from @mayank): Why is there a history length here when it doesn't mean anything in the sensor base?!?
# It is only for the contact sensor but there we should redefine the update function IMO.
if force_recompute or (self.cfg.history_length > 0):
# TODO (from @mayank): Why are we calling an attribute like this!? We should clean this up
# and make a function.
self.data
def debug_vis(self):
"""Visualizes the sensor data.
......@@ -192,9 +159,6 @@ class SensorBase(ABC):
Note:
Visualization of sensor data may add overhead to the simulation. It is recommended to disable
visualization when running the simulation in headless mode.
Args:
visualize (bool, optional): Whether to visualize the sensor data. Defaults to True.
"""
pass
......@@ -203,7 +167,7 @@ class SensorBase(ABC):
"""
@abstractmethod
def _buffer(self, env_ids: Optional[Sequence[int]] = None):
def _update_buffers(self, env_ids: Optional[Sequence[int]] = None):
"""Fills the buffers of the sensor data.
This function does not perform any time-based checks and directly fills the data into the data container.
......
......@@ -3,6 +3,9 @@
#
# SPDX-License-Identifier: BSD-3-Clause
from dataclasses import MISSING
from typing import ClassVar, Optional
from omni.isaac.orbit.utils import configclass
......@@ -10,11 +13,17 @@ from omni.isaac.orbit.utils import configclass
class SensorBaseCfg:
"""Configuration parameters for a sensor."""
update_freq: float = 0.0
"""Update frequency of the sensor buffers (in Hz). Defaults to 0.0.
cls_name: ClassVar[str] = MISSING
"""Name of the associated sensor class."""
prim_path_expr: Optional[str] = None
"""Relative path to the prim on which the sensor should be attached. Defaults to None."""
update_period: float = 0.0
"""Update period of the sensor buffers (in seconds). Defaults to 0.0 (update every step)."""
If the sensor frequency is zero, then the sensor buffers are filled at every simulation step.
"""
history_length: int = 0
"""Number of past frames to store in the sensor buffers. Defaults to 0 (no history)."""
debug_vis: bool = False
"""Whether to visualize the sensor. Defaults to False."""
......@@ -118,7 +118,7 @@ def create_prim_from_mesh(prim_path: str, vertices: np.ndarray, triangles: np.nd
improve_patch_friction = kwargs.get("improve_patch_friction", False)
physx_material_api.CreateImprovePatchFrictionAttr().Set(improve_patch_friction)
# set combination mode for coefficients
combine_mode = kwargs.get("combine_mode", "average")
combine_mode = kwargs.get("combine_mode", "multiply")
physx_material_api.CreateFrictionCombineModeAttr().Set(combine_mode)
physx_material_api.CreateRestitutionCombineModeAttr().Set(combine_mode)
# apply physics material to ground plane
......
......@@ -74,7 +74,7 @@ def create_ground_plane(
improve_patch_friction = kwargs.get("improve_patch_friction", False)
physx_material_api.CreateImprovePatchFrictionAttr().Set(improve_patch_friction)
# Set combination mode for coefficients
combine_mode = kwargs.get("combine_mode", "average")
combine_mode = kwargs.get("friciton_combine_mode", "multiply")
physx_material_api.CreateFrictionCombineModeAttr().Set(combine_mode)
physx_material_api.CreateRestitutionCombineModeAttr().Set(combine_mode)
# Apply physics material to ground plane
......@@ -83,7 +83,8 @@ def create_ground_plane(
prim_path, predicate=lambda x: prim_utils.get_prim_type_name(x) == "Plane"
)
)
GeometryPrim(collision_prim_path, collision=True).apply_physics_material(material)
geom_prim = GeometryPrim(collision_prim_path, disable_stablization=False, collision=True)
geom_prim.apply_physics_material(material)
# Change the color of the plane
# Warning: This is specific to the default grid plane asset.
if color is not None:
......
......@@ -371,7 +371,7 @@ Transformations
"""
@torch.jit.script
# @torch.jit.script
def combine_frame_transforms(
t01: torch.Tensor, q01: torch.Tensor, t12: torch.Tensor = None, q12: torch.Tensor = None
) -> Tuple[torch.Tensor, torch.Tensor]:
......
......@@ -33,6 +33,7 @@ simulation_app = SimulationApp(config)
"""Rest everything follows."""
import os
import torch
import carb
......@@ -111,6 +112,8 @@ def main():
usd_path = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmalC/anymal_c_minimal_instanceable.usd"
elif args_cli.asset == "oige":
usd_path = f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.usd"
elif os.path.exists(args_cli.asset):
usd_path = args_cli.asset
else:
raise ValueError(f"Invalid asset: {args_cli.asset}. Must be one of: orbit, oige.")
# add asset
......
......@@ -116,7 +116,7 @@ def main():
design_scene()
# Setup camera sensor
camera_cfg = PinholeCameraCfg(
update_freq=0,
update_period=0.0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors", "semantic_segmentation"],
......@@ -167,7 +167,7 @@ def main():
# Step simulation
sim.step(render=app_launcher.RENDER)
# Update camera data
camera.update_buffers(dt=0.0)
camera.update(dt=0.0)
# Print camera info
print(camera)
......@@ -197,7 +197,7 @@ def main():
else:
rep_output[key] = data
# Save images
rep_output["trigger_outputs"] = {"on_time": camera.frame[camera_index]}
rep_output["trigger_outputs"] = {"on_time": camera.timestamp[camera_index].item()}
rep_writer.write(rep_output)
......
......@@ -102,9 +102,10 @@ def main():
robot = LeggedRobot(cfg=ANYMAL_C_CFG)
robot.spawn("/World/envs/env_0/Robot")
# Contact sensor
contact_sensor_cfg = ContactSensorCfg(debug_vis=True)
contact_sensor_cfg = ContactSensorCfg(
prim_path_expr="Robot/.*_SHANK", debug_vis=False if args_cli.headless else True
)
contact_sensor = ContactSensor(cfg=contact_sensor_cfg)
contact_sensor.spawn("/World/envs/env_0/Robot/.*_SHANK")
# design props
design_scene()
......@@ -128,13 +129,14 @@ def main():
# Acquire handles
# Initialize handles
robot.initialize("/World/envs/env_.*/Robot")
contact_sensor.initialize("/World/envs/env_.*/Robot/.*_SHANK")
contact_sensor.initialize("/World/envs/env_.*")
print(contact_sensor)
# Now we are ready!
print("[INFO]: Setup complete...")
# dummy actions
actions = torch.zeros(robot.count, robot.num_actions, device=robot.device)
actions = robot.data.default_dof_pos
# Define simulation stepping
decimation = 4
......@@ -156,24 +158,29 @@ def main():
sim_time = 0.0
count = 0
# reset dof state
dof_pos, dof_vel = robot.get_default_dof_state()
dof_pos = robot.data.default_dof_pos
dof_vel = robot.data.default_dof_vel
robot.set_dof_state(dof_pos, dof_vel)
robot.reset_buffers()
# reset command
actions = torch.zeros(robot.count, robot.num_actions, device=robot.device)
actions = robot.data.default_dof_pos
# perform 4 steps
for _ in range(decimation):
# apply actions
robot.apply_action(actions)
robot.set_dof_position_targets(actions)
# write commands to sim
robot.write_commands_to_sim()
# perform step
sim.step(render=not args_cli.headless)
# fetch data
robot.refresh_sim_data(refresh_dofs=True)
# update sim-time
sim_time += sim_dt
count += 1
# update the buffers
if sim.is_playing():
robot.update_buffers(sim_dt)
contact_sensor.update_buffers(sim_dt)
contact_sensor.update(sim_dt, force_recompute=True)
# update marker visualization
if not args_cli.headless:
contact_sensor.debug_vis()
......
......@@ -51,7 +51,7 @@ from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.terrains as terrain_gen
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.sensors.ray_caster import GridPatternCfg, RayCaster, RayCasterCfg
from omni.isaac.orbit.terrains.config.rough import ASSORTED_TERRAINS_CFG
from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG
from omni.isaac.orbit.terrains.terrain_importer import TerrainImporter
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.orbit.utils.timer import Timer
......@@ -113,11 +113,13 @@ def main():
design_scene(sim=sim, num_envs=num_envs)
# Handler for terrains importing
if args_cli.terrain_type == "generated":
terrain_importer_cfg = terrain_gen.TerrainImporterCfg(prim_path="/World/ground", max_init_terrain_level=None)
terrain_importer = TerrainImporter(terrain_importer_cfg, device=sim.device)
terrain_generator = terrain_gen.TerrainGenerator(cfg=ASSORTED_TERRAINS_CFG, curriculum=True)
terrain_importer.import_mesh(terrain_generator.terrain_mesh, key="rough")
terrain_importer_cfg = terrain_gen.TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="generator",
terrain_generator=ROUGH_TERRAINS_CFG,
max_init_terrain_level=None,
)
terrain_importer = TerrainImporter(terrain_importer_cfg, num_envs=1, device=sim.device)
elif args_cli.terrain_type == "usd":
prim_utils.create_prim("/World/ground", usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd")
elif args_cli.terrain_type == "plane":
......@@ -128,7 +130,11 @@ def main():
# Create a ray-caster sensor
pattern_cfg = GridPatternCfg(resolution=0.1, size=(1.6, 1.0))
ray_caster_cfg = RayCasterCfg(
mesh_prim_paths=["/World/ground"], pattern_cfg=pattern_cfg, attach_yaw_only=True, debug_vis=True
prim_path_expr="ball",
mesh_prim_paths=["/World/ground"],
pattern_cfg=pattern_cfg,
attach_yaw_only=True,
debug_vis=False if args_cli.headless else True,
)
ray_caster = RayCaster(cfg=ray_caster_cfg)
# Create a view over all the balls
......@@ -141,7 +147,7 @@ def main():
# -- balls
ball_view.initialize()
# -- sensors
ray_caster.initialize("/World/envs/env_.*/ball")
ray_caster.initialize("/World/envs/env_.*")
# Print the sensor information
print(ray_caster)
......@@ -177,7 +183,7 @@ def main():
sim.step()
# Update the ray-caster
with Timer(f"Ray-caster update with {ray_caster.count} x {ray_caster.num_rays} rays"):
ray_caster.update_buffers(dt=sim.get_physics_dt())
ray_caster.update(dt=sim.get_physics_dt(), force_recompute=True)
# Visualize the ray-caster
if not args_cli.headless:
with Timer(f"Ray-caster debug visualization\t\t"):
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.3.2"
version = "0.4.0"
# Description
title = "ORBIT Environments"
......
......@@ -5,8 +5,8 @@ device: 'cuda:0'
policy:
init_noise_std: 1.0
actor_hidden_dims: [128, 128, 128]
critic_hidden_dims: [128, 128, 128]
actor_hidden_dims: [512, 256, 128]
critic_hidden_dims: [512, 256, 128]
activation: "elu" # can be elu, relu, selu, crelu, lrelu, tanh, sigmoid
# only required when "policy_class_name" is'ActorCriticRecurrent':
......@@ -19,7 +19,7 @@ algorithm:
value_loss_coef: 1.0
use_clipped_value_loss: True
clip_param: 0.2
entropy_coef: 0.01
entropy_coef: 0.005
num_learning_epochs: 5
num_mini_batches: 4 # mini batch size: num_envs * nsteps / nminibatches
learning_rate: 1.0e-3 # 5.e-4
......@@ -33,7 +33,8 @@ runner:
policy_class_name: "ActorCritic"
algorithm_class_name: "PPO"
num_steps_per_env: 24 # per iteration
max_iterations: 500 # number of policy updates
max_iterations: 1500 # number of policy updates
empirical_normalization: False
# logging
save_interval: 50 # check for potential saves every this many iterations
......
......@@ -2,6 +2,23 @@ Changelog
---------
0.4.0 (2023-07-26)
~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Removed the resetting of environment indices in the step call of the :class:`IsaacEnv` class.
This must be handled in the :math:`_step_impl`` function by the inherited classes.
* Adapted the wrapper for RSL-RL library its new API.
Fixed
^^^^^
* Added handling of no checkpoint available error in the :meth:`get_checkpoint_path`.
* Fixed the locomotion environment for rough terrain locomotion training.
0.3.2 (2023-07-22)
~~~~~~~~~~~~~~~~~~
......@@ -11,7 +28,6 @@ Added
* Added a UI to the :class:`IsaacEnv` class to enable/disable rendering of the viewport when not running in
headless mode.
Fixed
^^^^^
......
......@@ -31,13 +31,13 @@ The environments are then registered in the `omni/isaac/orbit_envs/__init__.py`:
```python
gym.register(
id="Isaac-Velocity-Anymal-C-v0",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:VelocityEnv",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnv",
kwargs={"cfg_entry_point": "omni.isaac.orbit_envs.locomotion.velocity.anymal_c.flat_terrain_cfg:FlatTerrainCfg"},
)
gym.register(
id="Isaac-Velocity-A1-v0",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:VelocityEnv",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnv",
kwargs={"cfg_entry_point": "omni.isaac.orbit_envs.locomotion.velocity.a1.flat_terrain_cfg:FlatTerrainCfg"},
)
```
......
......@@ -72,9 +72,15 @@ gym.register(
##
gym.register(
id="Isaac-Velocity-Anymal-C-v0",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:VelocityEnv",
kwargs={"cfg_entry_point": "omni.isaac.orbit_envs.locomotion.velocity:VelocityEnvCfg"},
id="Isaac-Velocity-Rough-Anymal-C-v0",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnv",
kwargs={"cfg_entry_point": "omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnvRoughCfg"},
)
gym.register(
id="Isaac-Velocity-Rough-Anymal-C-Play-v0",
entry_point="omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnv",
kwargs={"cfg_entry_point": "omni.isaac.orbit_envs.locomotion.velocity:LocomotionEnvRoughCfg_PLAY"},
)
##
......
......@@ -151,6 +151,13 @@ class AntEnv(IsaacEnv):
self.episode_length_buf[env_ids] = 0
def _step_impl(self, actions: torch.Tensor):
# reset environments that terminated
reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(reset_env_ids) > 0:
self._reset_idx(reset_env_ids)
# increment the number of steps
self.episode_length_buf += 1
# store actions into local
self.actions = actions.clone().to(device=self.device)
# pre-step: set actions into buffer
......
......@@ -126,6 +126,13 @@ class CartpoleEnv(IsaacEnv):
self.episode_length_buf[env_ids] = 0
def _step_impl(self, actions: torch.Tensor):
# reset environments that terminated
reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(reset_env_ids) > 0:
self._reset_idx(reset_env_ids)
# increment the number of steps
self.episode_length_buf += 1
# pre-step: set actions into buffer
self.actions = actions.clone().to(device=self.device)
dof_forces = torch.zeros(
......
......@@ -153,6 +153,13 @@ class HumanoidEnv(IsaacEnv):
self.episode_length_buf[env_ids] = 0
def _step_impl(self, actions: torch.Tensor):
# reset environments that terminated
reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(reset_env_ids) > 0:
self._reset_idx(reset_env_ids)
# increment the number of steps
self.episode_length_buf += 1
# pre-step: set actions into buffer
self.actions = actions.clone().to(device=self.device)
dof_forces = self.actions * self._JOINT_GEARS * self.cfg_dict["env"]["power_scale"]
......
......@@ -23,6 +23,9 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.orbit.sensors import * # noqa: F401, F403
from omni.isaac.orbit.sensors.sensor_base import SensorBase
from .isaac_env_cfg import IsaacEnvCfg
# Define type aliases here to avoid circular import
......@@ -180,13 +183,14 @@ class IsaacEnv(gym.Env):
self.sim.add_timeline_callback("close_env_on_stop", self._stop_simulation_callback)
# initialize common environment buffers
self.obs_buf: VecEnvObs = None
self.reward_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.float)
self.reset_buf = torch.ones(self.num_envs, device=self.device, dtype=torch.long)
self.episode_length_buf = torch.zeros(self.num_envs, device=self.device, dtype=torch.long)
# allocate dictionary to store metrics
self.extras = {}
# create a dictionary to store the sensors
self.sensors = dict()
# create cloner for duplicating the scenes
cloner = GridCloner(spacing=self.cfg.env.env_spacing)
cloner.define_base_env(self.env_ns)
......@@ -206,7 +210,9 @@ class IsaacEnv(gym.Env):
replicate_physics=self.cfg.sim.replicate_physics,
)
# convert environment positions to torch tensor
self.envs_positions = torch.tensor(self.envs_positions, dtype=torch.float, device=self.device)
# self.envs_positions = torch.tensor(self.envs_positions, dtype=torch.float, device=self.device)
# TODO Move to right position
self.envs_positions = self.terrain_importer.env_origins
# filter collisions within each environment instance
physics_scene_path = self.sim.get_physics_context().prim_path
cloner.filter_collisions(
......@@ -268,13 +274,11 @@ class IsaacEnv(gym.Env):
indices = torch.arange(self.num_envs, dtype=torch.int64, device=self.device)
self._reset_idx(indices)
# perform one step to have buffers into action
self.sim.step(render=False)
self.sim.step(render=False) # TODO why do we need this ?
# compute common quantities
self._cache_common_quantities()
# compute observations
self.obs_buf = self._get_observations()
# return observations
return self.obs_buf
return self._get_observations()
def step(self, actions: torch.Tensor) -> VecEnvStepReturn:
"""Reset any terminated environments and apply actions on the environment.
......@@ -291,11 +295,6 @@ class IsaacEnv(gym.Env):
Args:
actions (torch.Tensor): Actions to apply on the simulator.
Note:
We perform resetting of the terminated environments before simulation
stepping. This is because the physics buffers are not forwarded until
the physics step occurs.
Returns:
VecEnvStepReturn: A tuple containing:
- (VecEnvObs) observations from the environment
......@@ -317,16 +316,8 @@ class IsaacEnv(gym.Env):
# FIXME: This steps physics as well, which we is not good in general.
self.sim.app.update()
# reset environments that terminated
reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(reset_env_ids) > 0:
self._reset_idx(reset_env_ids)
# increment the number of steps
self.episode_length_buf += 1
# perform the stepping of simulation
self._step_impl(actions)
# compute observations
self.obs_buf = self._get_observations()
# periodically update the UI to keep it responsive
if self.render_mode == RenderMode.NO_RENDERING:
......@@ -340,13 +331,13 @@ class IsaacEnv(gym.Env):
if self._flatcache_iface is not None:
self._flatcache_iface.update(0.0, 0.0)
# perform debug visualization
if self.enable_render and self.cfg.env.debug_vis:
if self.cfg.viewer.debug_vis:
self._debug_vis()
# render the scene
self.sim.render()
# return observations, rewards, resets and extras
return self.obs_buf, self.reward_buf, self.reset_buf, self.extras
return self._get_observations(), self.reward_buf, self.reset_buf, self.extras
def render(self, mode: str = "human") -> Optional[np.ndarray]:
"""Run rendering without stepping through the physics.
......@@ -394,14 +385,27 @@ class IsaacEnv(gym.Env):
if not self._is_closed:
# stop physics simulation (precautionary)
self.sim.stop()
# cleanup the scene and callbacks
self.sim.clear_all_callbacks()
# destroy the orbit window
if self._orbit_window is not None:
self._orbit_window.destroy()
# update closing status
self._is_closed = True
"""
Operations - Scene
"""
def enable_sensor(self, sensor_name: str):
"""Adds a sensor to the environment.
Args:
sensor_name (str): Name of the sensor to add.
"""
sensor_cfg = self.cfg.sensors.__getattribute__(sensor_name)
if sensor_name not in self.sensors.keys():
sensor: SensorBase = eval(sensor_cfg.cls_name)(sensor_cfg)
# sensor.spawn("") # TODO: do we need to call spawn earlier?
sensor.initialize(self.env_ns + "/.*")
self.sensors[sensor_name] = sensor
"""
Implementation specifics.
"""
......@@ -433,11 +437,11 @@ class IsaacEnv(gym.Env):
@abc.abstractmethod
def _step_impl(self, actions: torch.Tensor):
"""Apply actions on the environment and computes MDP signals.
"""Apply actions on the environment, computes MDP signals and perform resets.
This function sets the simulation buffers for actions to apply, perform
stepping of the simulation, and compute the MDP signals for reward and
termination.
stepping of the simulation, computes the MDP signals for reward and
termination, and perform resetting of the environment based on their termination.
Note:
The environment specific implementation of this function is responsible for also
......@@ -598,21 +602,29 @@ class IsaacEnv(gym.Env):
import omni.isaac.ui.ui_utils as ui_utils
import omni.ui as ui
# do a sim update to finish loading
for _ in range(10):
self.sim.app.update()
# acquire viewport window
self._viewport_window = ui.Workspace.get_window("Viewport")
# create window for UI
self._orbit_window = omni.ui.Window(
"Orbit", width=500, height=0, visible=True, dock_preference=ui.DockPreference.RIGHT_TOP
"Orbit", width=400, height=500, visible=True, dock_preference=ui.DockPreference.RIGHT_TOP
)
# dock next to properties window
property_window = ui.Workspace.get_window("Property")
self._orbit_window.dock_in(property_window, ui.DockPosition.SAME, 1.0)
self._orbit_window.focus()
# do a sim update to finish loading
for _ in range(10):
self.sim.app.update()
# keep a dictionary of stacks so that child environments can add their own UI elements
# this can be done by using the `with` context manager
self._orbit_window_elements = dict()
# create main frame
with self._orbit_window.frame:
self._orbit_window_elements["main_frame"] = self._orbit_window.frame
with self._orbit_window_elements["main_frame"]:
# create main stack
self._orbit_window_elements["main_vstack"] = ui.VStack(spacing=5, height=0)
with self._orbit_window_elements["main_vstack"]:
......@@ -639,7 +651,7 @@ class IsaacEnv(gym.Env):
"tooltip": "Select a rendering mode",
"on_clicked_fn": self._on_render_mode_select,
}
_ = ui_utils.dropdown_builder(**render_mode_cfg)
self._orbit_window_elements["render_dropdown"] = ui_utils.dropdown_builder(**render_mode_cfg)
# create debug visualization checkbox
debug_vis_checkbox = {
"label": "Debug Visualization",
......@@ -648,7 +660,7 @@ class IsaacEnv(gym.Env):
"tooltip": "Toggle environment debug visualization",
"on_clicked_fn": self._toggle_debug_visualization_flag,
}
_ = ui_utils.cb_builder(**debug_vis_checkbox)
self._orbit_window_elements["debug_checkbox"] = ui_utils.cb_builder(**debug_vis_checkbox)
def _on_render_mode_select(self, value: str):
"""Callback for when the rendering mode is selected."""
......
......@@ -32,6 +32,8 @@ class EnvCfg:
"""Spacing between cloned environments."""
episode_length_s: float = None
"""Duration of an episode (in seconds). Default is None (no limit)."""
send_time_outs: bool = True
"""Whether to send time-outs to the algorithm. Default is True."""
@configclass
......
import torch
from typing import TYPE_CHECKING, Sequence
if TYPE_CHECKING:
from .velocity.locomotion_env import LocomotionEnv
def terrain_levels_vel(env: "LocomotionEnv", env_ids: Sequence[int]) -> torch.Tensor:
"""
If the robot walked more than half the terrain length if moves to a harder level.
Else if it walked less than half of the distance required by the commanded velocity, it goes to a simpler level
"""
distance = torch.norm(env.robot.data.root_pos_w[env_ids, :2] - env.terrain_importer.env_origins[env_ids, :2], dim=1)
# robots that walked far enough progress to harder terrains
move_up = distance > env.cfg.terrain.terrain_generator.size[0] / 2
# robots that walked less than half of their required distance go to simpler terrains
move_down = (
distance < torch.norm(env._command_manager.command[env_ids, :2], dim=1) * env.max_episode_length * env.dt * 0.5
)
move_down *= ~move_up
# update terrain levels
env.terrain_importer.update_env_origins(env_ids, move_up, move_down)
return torch.mean(env.terrain_importer.terrain_levels.float())
......@@ -32,12 +32,12 @@ def velocity_commands(env: "LocomotionEnv"):
def dof_pos(env: "LocomotionEnv"):
"""DOF positions for legs offset by the drive default positions."""
return env.robot.data.dof_pos - env.robot.data.actuator_pos_offset
return env.robot.data.dof_pos - env.robot.data.default_dof_pos
def dof_vel(env: "LocomotionEnv"):
"""DOF velocity of the legs."""
return env.robot.data.dof_vel - env.robot.data.actuator_vel_offset
return env.robot.data.dof_vel - env.robot.data.default_dof_vel
def actions(env: "LocomotionEnv"):
......
......@@ -5,7 +5,7 @@
"""Velocity-based locomotion environments for legged robots."""
from .velocity_cfg import VelocityEnvCfg
from .velocity_env import VelocityEnv
from .locomotion_cfg import LocomotionEnvCfg, LocomotionEnvRoughCfg, LocomotionEnvRoughCfg_PLAY
from .locomotion_env import LocomotionEnv
__all__ = ["VelocityEnv", "VelocityEnvCfg"]
__all__ = ["LocomotionEnv", "LocomotionEnvRoughCfg", "LocomotionEnvRoughCfg_PLAY"]
......@@ -137,6 +137,13 @@ class LiftEnv(IsaacEnv):
self._ik_controller.reset_idx(env_ids)
def _step_impl(self, actions: torch.Tensor):
# reset environments that terminated
reset_env_ids = self.reset_buf.nonzero(as_tuple=False).squeeze(-1)
if len(reset_env_ids) > 0:
self._reset_idx(reset_env_ids)
# increment the number of steps
self.episode_length_buf += 1
# pre-step: set actions into buffer
self.actions = actions.clone().to(device=self.device)
# transform actions based on controller
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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