Unverified Commit 52af8996 authored by Masoud Moghani's avatar Masoud Moghani Committed by GitHub

Adds visualization markers customization for the MDP command terms (#841)

# Description

This MR allows users to customize the visualization markers for the MDP
command terms. It puts them in the command term configuration file
instead of hard-coding them into the code.

## Type of change

- New feature (non-breaking change which adds functionality)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent e83f79e3
[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"
......
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)
~~~~~~~~~~~~~~~~~~~~
......
......@@ -7,6 +7,8 @@ import math
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
......@@ -62,6 +64,20 @@ class UniformVelocityCommandCfg(CommandTermCfg):
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):
......@@ -125,6 +141,18 @@ class UniformPoseCommandCfg(CommandTermCfg):
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):
......@@ -158,6 +186,14 @@ class UniformPose2dCommandCfg(CommandTermCfg):
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):
......
......@@ -14,7 +14,6 @@ from typing import TYPE_CHECKING
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
......@@ -124,20 +123,17 @@ class UniformPose2dCommand(CommandTerm):
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),
......
......@@ -14,7 +14,6 @@ from typing import TYPE_CHECKING
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:
......@@ -131,21 +130,17 @@ class UniformPoseCommand(CommandTerm):
# 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
......@@ -157,4 +152,4 @@ class UniformPoseCommand(CommandTerm):
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])
......@@ -15,7 +15,6 @@ import omni.isaac.lab.utils.math as math_utils
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
......@@ -148,24 +147,18 @@ class UniformVelocityCommand(CommandTerm):
# 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
......@@ -180,8 +173,8 @@ class UniformVelocityCommand(CommandTerm):
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.
......@@ -190,7 +183,7 @@ class UniformVelocityCommand(CommandTerm):
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
......
......@@ -9,10 +9,10 @@ import torch
import omni.isaac.lab.envs.mdp as mdp
import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.managers import EventTermCfg as EventTerm
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.assets import Articulation, ArticulationCfg
from omni.isaac.lab.envs import DirectRLEnv, DirectRLEnvCfg
from omni.isaac.lab.managers import EventTermCfg as EventTerm
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.scene import InteractiveSceneCfg
from omni.isaac.lab.sensors import ContactSensor, ContactSensorCfg, RayCaster, RayCasterCfg, patterns
from omni.isaac.lab.sim import SimulationCfg
......
......@@ -55,7 +55,7 @@ class InHandReOrientationCommandCfg(CommandTermCfg):
Otherwise, the marker may occlude the object in the visualization.
"""
visualizer_cfg: VisualizationMarkersCfg = VisualizationMarkersCfg(
goal_pose_visualizer_cfg: VisualizationMarkersCfg = VisualizationMarkersCfg(
prim_path="/Visuals/Command/goal_marker",
markers={
"goal": sim_utils.UsdFileCfg(
......@@ -64,4 +64,4 @@ class InHandReOrientationCommandCfg(CommandTermCfg):
),
},
)
"""Configuration for the visualization markers. Default is a cube marker."""
"""The configuration for the goal pose visualization marker. Defaults to a DexCube marker."""
......@@ -128,17 +128,17 @@ class InHandReOrientationCommand(CommandTerm):
# note: parent only deals with callbacks. not their visibility
if debug_vis:
# create markers if necessary for the first time
if not hasattr(self, "goal_marker_visualizer"):
self.goal_marker_visualizer = VisualizationMarkers(self.cfg.visualizer_cfg)
if not hasattr(self, "goal_pose_visualizer"):
self.goal_pose_visualizer = VisualizationMarkers(self.cfg.goal_pose_visualizer_cfg)
# set visibility
self.goal_marker_visualizer.set_visibility(True)
self.goal_pose_visualizer.set_visibility(True)
else:
if hasattr(self, "goal_marker_visualizer"):
self.goal_marker_visualizer.set_visibility(False)
if hasattr(self, "goal_pose_visualizer"):
self.goal_pose_visualizer.set_visibility(False)
def _debug_vis_callback(self, event):
# add an offset to the marker position to visualize the goal
marker_pos = self.pos_command_w + torch.tensor(self.cfg.marker_pos_offset, device=self.device)
marker_quat = self.quat_command_w
# visualize the goal marker
self.goal_marker_visualizer.visualize(translations=marker_pos, orientations=marker_quat)
self.goal_pose_visualizer.visualize(translations=marker_pos, orientations=marker_quat)
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