Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/main' into main
Browse files Browse the repository at this point in the history
  • Loading branch information
fan-ziqi committed Sep 20, 2024
2 parents 245fe57 + 55ab947 commit a509893
Show file tree
Hide file tree
Showing 18 changed files with 220 additions and 67 deletions.
12 changes: 6 additions & 6 deletions docs/source/features/environments.rst
Original file line number Diff line number Diff line change
Expand Up @@ -165,14 +165,14 @@ Environments based on legged locomotion tasks.
.. |velocity-flat-anymal-d-link| replace:: `Isaac-Velocity-Flat-Anymal-D-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py>`__
.. |velocity-rough-anymal-d-link| replace:: `Isaac-Velocity-Rough-Anymal-D-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py>`__

.. |velocity-flat-unitree-a1-link| replace:: `Isaac-Velocity-Flat-Unitree-A1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_a1/flat_env_cfg.py>`__
.. |velocity-rough-unitree-a1-link| replace:: `Isaac-Velocity-Rough-Unitree-A1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_a1/rough_env_cfg.py>`__
.. |velocity-flat-unitree-a1-link| replace:: `Isaac-Velocity-Flat-Unitree-A1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/a1/flat_env_cfg.py>`__
.. |velocity-rough-unitree-a1-link| replace:: `Isaac-Velocity-Rough-Unitree-A1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py>`__

.. |velocity-flat-unitree-go1-link| replace:: `Isaac-Velocity-Flat-Unitree-Go1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_go1/flat_env_cfg.py>`__
.. |velocity-rough-unitree-go1-link| replace:: `Isaac-Velocity-Rough-Unitree-Go1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_go1/rough_env_cfg.py>`__
.. |velocity-flat-unitree-go1-link| replace:: `Isaac-Velocity-Flat-Unitree-Go1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/go1/flat_env_cfg.py>`__
.. |velocity-rough-unitree-go1-link| replace:: `Isaac-Velocity-Rough-Unitree-Go1-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py>`__

.. |velocity-flat-unitree-go2-link| replace:: `Isaac-Velocity-Flat-Unitree-Go2-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_go2/flat_env_cfg.py>`__
.. |velocity-rough-unitree-go2-link| replace:: `Isaac-Velocity-Rough-Unitree-Go2-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/unitree_go2/rough_env_cfg.py>`__
.. |velocity-flat-unitree-go2-link| replace:: `Isaac-Velocity-Flat-Unitree-Go2-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/go2/flat_env_cfg.py>`__
.. |velocity-rough-unitree-go2-link| replace:: `Isaac-Velocity-Rough-Unitree-Go2-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py>`__

.. |velocity-flat-spot-link| replace:: `Isaac-Velocity-Flat-Spot-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py>`__

Expand Down
2 changes: 1 addition & 1 deletion source/extensions/omni.isaac.lab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.22.11"
version = "0.22.12"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
10 changes: 10 additions & 0 deletions source/extensions/omni.isaac.lab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,16 @@
Changelog
---------

0.22.12 (2024-09-08)
~~~~~~~~~~~~~~~~~~~~

Changed
^^^^^^^

* Moved the configuration of visualization markers for the command terms to their respective configuration classes.
This allows users to modify the markers for the command terms without having to modify the command term classes.


0.22.11 (2024-09-10)
~~~~~~~~~~~~~~~~~~~~

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -954,6 +954,7 @@ def _create_buffers(self):

# -- bodies
self._data.default_mass = self.root_physx_view.get_masses().clone()
self._data.default_inertia = self.root_physx_view.get_inertias().clone()

# -- default joint state
self._data.default_joint_pos = torch.zeros(self.num_instances, self.num_joints, device=self.device)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,13 @@ def update(self, dt: float):
default_mass: torch.Tensor = None
"""Default mass read from the simulation. Shape is (num_instances, num_bodies)."""

default_inertia: torch.Tensor = None
"""Default inertia read from the simulation. Shape is (num_instances, num_bodies, 9).
The inertia is the inertia tensor relative to the center of mass frame. The values are stored in
the order :math:`[I_{xx}, I_{xy}, I_{xz}, I_{yx}, I_{yy}, I_{yz}, I_{zx}, I_{zy}, I_{zz}]`.
"""

default_joint_pos: torch.Tensor = None
"""Default joint positions of all joints. Shape is (num_instances, num_joints)."""

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,7 @@ def _create_buffers(self):
# set information about rigid body into data
self._data.body_names = self.body_names
self._data.default_mass = self.root_physx_view.get_masses().clone()
self._data.default_inertia = self.root_physx_view.get_inertias().clone()

def _process_cfg(self):
"""Post processing of configuration parameters."""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,13 @@ def update(self, dt: float):
default_mass: torch.Tensor = None
"""Default mass read from the simulation. Shape is (num_instances, 1)."""

default_inertia: torch.Tensor = None
"""Default inertia tensor read from the simulation. Shape is (num_instances, 9).
The inertia is the inertia tensor relative to the center of mass frame. The values are stored in
the order :math:`[I_{xx}, I_{xy}, I_{xz}, I_{yx}, I_{yy}, I_{yz}, I_{zx}, I_{zy}, I_{zz}]`.
"""

##
# Properties.
##
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
from dataclasses import MISSING

from omni.isaac.lab.managers import CommandTermCfg
from omni.isaac.lab.markers import VisualizationMarkersCfg
from omni.isaac.lab.markers.config import BLUE_ARROW_X_MARKER_CFG, FRAME_MARKER_CFG, GREEN_ARROW_X_MARKER_CFG
from omni.isaac.lab.utils import configclass

from .null_command import NullCommand
Expand Down Expand Up @@ -62,6 +64,20 @@ class Ranges:
ranges: Ranges = MISSING
"""Distribution ranges for the velocity commands."""

goal_vel_visualizer_cfg: VisualizationMarkersCfg = GREEN_ARROW_X_MARKER_CFG.replace(
prim_path="/Visuals/Command/velocity_goal"
)
"""The configuration for the goal velocity visualization marker. Defaults to GREEN_ARROW_X_MARKER_CFG."""

current_vel_visualizer_cfg: VisualizationMarkersCfg = BLUE_ARROW_X_MARKER_CFG.replace(
prim_path="/Visuals/Command/velocity_current"
)
"""The configuration for the current velocity visualization marker. Defaults to BLUE_ARROW_X_MARKER_CFG."""

# Set the scale of the visualization markers to (0.5, 0.5, 0.5)
goal_vel_visualizer_cfg.markers["arrow"].scale = (0.5, 0.5, 0.5)
current_vel_visualizer_cfg.markers["arrow"].scale = (0.5, 0.5, 0.5)


@configclass
class NormalVelocityCommandCfg(UniformVelocityCommandCfg):
Expand Down Expand Up @@ -125,6 +141,18 @@ class Ranges:
ranges: Ranges = MISSING
"""Ranges for the commands."""

goal_pose_visualizer_cfg: VisualizationMarkersCfg = FRAME_MARKER_CFG.replace(prim_path="/Visuals/Command/goal_pose")
"""The configuration for the goal pose visualization marker. Defaults to FRAME_MARKER_CFG."""

current_pose_visualizer_cfg: VisualizationMarkersCfg = FRAME_MARKER_CFG.replace(
prim_path="/Visuals/Command/body_pose"
)
"""The configuration for the current pose visualization marker. Defaults to FRAME_MARKER_CFG."""

# Set the scale of the visualization markers to (0.1, 0.1, 0.1)
goal_pose_visualizer_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
current_pose_visualizer_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)


@configclass
class UniformPose2dCommandCfg(CommandTermCfg):
Expand Down Expand Up @@ -158,6 +186,14 @@ class Ranges:
ranges: Ranges = MISSING
"""Distribution ranges for the position commands."""

goal_pose_visualizer_cfg: VisualizationMarkersCfg = GREEN_ARROW_X_MARKER_CFG.replace(
prim_path="/Visuals/Command/pose_goal"
)
"""The configuration for the goal pose visualization marker. Defaults to GREEN_ARROW_X_MARKER_CFG."""

# Set the scale of the visualization markers to (0.2, 0.2, 0.8)
goal_pose_visualizer_cfg.markers["arrow"].scale = (0.2, 0.2, 0.8)


@configclass
class TerrainBasedPose2dCommandCfg(UniformPose2dCommandCfg):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
from omni.isaac.lab.assets import Articulation
from omni.isaac.lab.managers import CommandTerm
from omni.isaac.lab.markers import VisualizationMarkers
from omni.isaac.lab.markers.config import GREEN_ARROW_X_MARKER_CFG
from omni.isaac.lab.terrains import TerrainImporter
from omni.isaac.lab.utils.math import quat_from_euler_xyz, quat_rotate_inverse, wrap_to_pi, yaw_quat

Expand Down Expand Up @@ -124,20 +123,17 @@ def _update_command(self):
def _set_debug_vis_impl(self, debug_vis: bool):
# create markers if necessary for the first tome
if debug_vis:
if not hasattr(self, "arrow_goal_visualizer"):
marker_cfg = GREEN_ARROW_X_MARKER_CFG.copy()
marker_cfg.markers["arrow"].scale = (0.2, 0.2, 0.8)
marker_cfg.prim_path = "/Visuals/Command/pose_goal"
self.arrow_goal_visualizer = VisualizationMarkers(marker_cfg)
if not hasattr(self, "goal_pose_visualizer"):
self.goal_pose_visualizer = VisualizationMarkers(self.cfg.goal_pose_visualizer_cfg)
# set their visibility to true
self.arrow_goal_visualizer.set_visibility(True)
self.goal_pose_visualizer.set_visibility(True)
else:
if hasattr(self, "arrow_goal_visualizer"):
self.arrow_goal_visualizer.set_visibility(False)
if hasattr(self, "goal_pose_visualizer"):
self.goal_pose_visualizer.set_visibility(False)

def _debug_vis_callback(self, event):
# update the box marker
self.arrow_goal_visualizer.visualize(
self.goal_pose_visualizer.visualize(
translations=self.pos_command_w,
orientations=quat_from_euler_xyz(
torch.zeros_like(self.heading_command_w),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
from omni.isaac.lab.assets import Articulation
from omni.isaac.lab.managers import CommandTerm
from omni.isaac.lab.markers import VisualizationMarkers
from omni.isaac.lab.markers.config import FRAME_MARKER_CFG
from omni.isaac.lab.utils.math import combine_frame_transforms, compute_pose_error, quat_from_euler_xyz, quat_unique

if TYPE_CHECKING:
Expand Down Expand Up @@ -131,21 +130,17 @@ def _set_debug_vis_impl(self, debug_vis: bool):
# create markers if necessary for the first tome
if debug_vis:
if not hasattr(self, "goal_pose_visualizer"):
marker_cfg = FRAME_MARKER_CFG.copy()
marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
# -- goal pose
marker_cfg.prim_path = "/Visuals/Command/goal_pose"
self.goal_pose_visualizer = VisualizationMarkers(marker_cfg)
self.goal_pose_visualizer = VisualizationMarkers(self.cfg.goal_pose_visualizer_cfg)
# -- current body pose
marker_cfg.prim_path = "/Visuals/Command/body_pose"
self.body_pose_visualizer = VisualizationMarkers(marker_cfg)
self.current_pose_visualizer = VisualizationMarkers(self.cfg.current_pose_visualizer_cfg)
# set their visibility to true
self.goal_pose_visualizer.set_visibility(True)
self.body_pose_visualizer.set_visibility(True)
self.current_pose_visualizer.set_visibility(True)
else:
if hasattr(self, "goal_pose_visualizer"):
self.goal_pose_visualizer.set_visibility(False)
self.body_pose_visualizer.set_visibility(False)
self.current_pose_visualizer.set_visibility(False)

def _debug_vis_callback(self, event):
# check if robot is initialized
Expand All @@ -157,4 +152,4 @@ def _debug_vis_callback(self, event):
self.goal_pose_visualizer.visualize(self.pose_command_w[:, :3], self.pose_command_w[:, 3:])
# -- current body pose
body_pose_w = self.robot.data.body_state_w[:, self.body_idx]
self.body_pose_visualizer.visualize(body_pose_w[:, :3], body_pose_w[:, 3:7])
self.current_pose_visualizer.visualize(body_pose_w[:, :3], body_pose_w[:, 3:7])
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
from omni.isaac.lab.assets import Articulation
from omni.isaac.lab.managers import CommandTerm
from omni.isaac.lab.markers import VisualizationMarkers
from omni.isaac.lab.markers.config import BLUE_ARROW_X_MARKER_CFG, GREEN_ARROW_X_MARKER_CFG

if TYPE_CHECKING:
from omni.isaac.lab.envs import ManagerBasedEnv
Expand Down Expand Up @@ -148,24 +147,18 @@ def _set_debug_vis_impl(self, debug_vis: bool):
# note: parent only deals with callbacks. not their visibility
if debug_vis:
# create markers if necessary for the first tome
if not hasattr(self, "base_vel_goal_visualizer"):
if not hasattr(self, "goal_vel_visualizer"):
# -- goal
marker_cfg = GREEN_ARROW_X_MARKER_CFG.copy()
marker_cfg.prim_path = "/Visuals/Command/velocity_goal"
marker_cfg.markers["arrow"].scale = (0.5, 0.5, 0.5)
self.base_vel_goal_visualizer = VisualizationMarkers(marker_cfg)
self.goal_vel_visualizer = VisualizationMarkers(self.cfg.goal_vel_visualizer_cfg)
# -- current
marker_cfg = BLUE_ARROW_X_MARKER_CFG.copy()
marker_cfg.prim_path = "/Visuals/Command/velocity_current"
marker_cfg.markers["arrow"].scale = (0.5, 0.5, 0.5)
self.base_vel_visualizer = VisualizationMarkers(marker_cfg)
self.current_vel_visualizer = VisualizationMarkers(self.cfg.current_vel_visualizer_cfg)
# set their visibility to true
self.base_vel_goal_visualizer.set_visibility(True)
self.base_vel_visualizer.set_visibility(True)
self.goal_vel_visualizer.set_visibility(True)
self.current_vel_visualizer.set_visibility(True)
else:
if hasattr(self, "base_vel_goal_visualizer"):
self.base_vel_goal_visualizer.set_visibility(False)
self.base_vel_visualizer.set_visibility(False)
if hasattr(self, "goal_vel_visualizer"):
self.goal_vel_visualizer.set_visibility(False)
self.current_vel_visualizer.set_visibility(False)

def _debug_vis_callback(self, event):
# check if robot is initialized
Expand All @@ -180,8 +173,8 @@ def _debug_vis_callback(self, event):
vel_des_arrow_scale, vel_des_arrow_quat = self._resolve_xy_velocity_to_arrow(self.command[:, :2])
vel_arrow_scale, vel_arrow_quat = self._resolve_xy_velocity_to_arrow(self.robot.data.root_lin_vel_b[:, :2])
# display markers
self.base_vel_goal_visualizer.visualize(base_pos_w, vel_des_arrow_quat, vel_des_arrow_scale)
self.base_vel_visualizer.visualize(base_pos_w, vel_arrow_quat, vel_arrow_scale)
self.goal_vel_visualizer.visualize(base_pos_w, vel_des_arrow_quat, vel_des_arrow_scale)
self.current_vel_visualizer.visualize(base_pos_w, vel_arrow_quat, vel_arrow_scale)

"""
Internal helpers.
Expand All @@ -190,7 +183,7 @@ def _debug_vis_callback(self, event):
def _resolve_xy_velocity_to_arrow(self, xy_velocity: torch.Tensor) -> tuple[torch.Tensor, torch.Tensor]:
"""Converts the XY base velocity command to arrow direction rotation."""
# obtain default scale of the marker
default_scale = self.base_vel_goal_visualizer.cfg.markers["arrow"].scale
default_scale = self.goal_vel_visualizer.cfg.markers["arrow"].scale
# arrow-scale
arrow_scale = torch.tensor(default_scale, device=self.device).repeat(xy_velocity.shape[0], 1)
arrow_scale[:, 0] *= torch.linalg.norm(xy_velocity, dim=1) * 3.0
Expand Down
27 changes: 27 additions & 0 deletions source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py
Original file line number Diff line number Diff line change
Expand Up @@ -132,12 +132,18 @@ def randomize_rigid_body_mass(
mass_distribution_params: tuple[float, float],
operation: Literal["add", "scale", "abs"],
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
recompute_inertia: bool = True,
):
"""Randomize the mass of the bodies by adding, scaling, or setting random values.
This function allows randomizing the mass of the bodies of the asset. The function samples random values from the
given distribution parameters and adds, scales, or sets the values into the physics simulation based on the operation.
If the ``recompute_inertia`` flag is set to ``True``, the function recomputes the inertia tensor of the bodies
after setting the mass. This is useful when the mass is changed significantly, as the inertia tensor depends
on the mass. It assumes the body is a uniform density object. If the body is not a uniform density object,
the inertia tensor may not be accurate.
.. tip::
This function uses CPU tensors to assign the body masses. It is recommended to use this function
only during the initialization of the environment.
Expand All @@ -159,7 +165,10 @@ def randomize_rigid_body_mass(

# get the current masses of the bodies (num_assets, num_bodies)
masses = asset.root_physx_view.get_masses()

# apply randomization on default values
# this is to make sure when calling the function multiple times, the randomization is applied on the
# default values and not the previously randomized values
masses[env_ids[:, None], body_ids] = asset.data.default_mass[env_ids[:, None], body_ids].clone()

# sample from the given range
Expand All @@ -172,6 +181,24 @@ def randomize_rigid_body_mass(
# set the mass into the physics simulation
asset.root_physx_view.set_masses(masses, env_ids)

# recompute inertia tensors if needed
if recompute_inertia:
# compute the ratios of the new masses to the initial masses
ratios = masses[env_ids[:, None], body_ids] / asset.data.default_mass[env_ids[:, None], body_ids]
# scale the inertia tensors by the the ratios
# since mass randomization is done on default values, we can use the default inertia tensors
inertias = asset.root_physx_view.get_inertias()
if isinstance(asset, Articulation):
# inertia has shape: (num_envs, num_bodies, 9) for articulation
inertias[env_ids[:, None], body_ids] = (
asset.data.default_inertia[env_ids[:, None], body_ids] * ratios[..., None]
)
else:
# inertia has shape: (num_envs, 9) for rigid object
inertias[env_ids] = asset.data.default_inertia[env_ids] * ratios
# set the inertia tensors into the physics simulation
asset.root_physx_view.set_inertias(inertias, env_ids)


def randomize_physics_scene_gravity(
env: ManagerBasedEnv,
Expand Down
Loading

0 comments on commit a509893

Please sign in to comment.