Unverified Commit 69df26b7 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Switches from `carb` to `omni.log` for logging (#1215)

# Description

Earlier, we used [`Carbonite
SDK`](https://docs.omniverse.nvidia.com/kit/docs/carbonite/latest/api/dir_carb_logging.html)
to log directly. However, this has limited functionalities compared to
[`omni.log`](https://docs.omniverse.nvidia.com/kit/docs/carbonite/latest/api/namespace_omni__log.html)
in Omniverse. Using `omni.log`, you can fine-grain the channels and
print levels better.

Link to omni.log documentation:
https://docs.omniverse.nvidia.com/kit/docs/carbonite/latest/docs/omni.log/Logging.html

This MR migrates all `carb` references to the new API.

## Type of change

- Bug fix (non-breaking change which fixes an issue)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)

## Screenshot

Checking the performance:
```
./isaaclab.sh -p source/standalone/benchmarks/benchmark_load_robot.py --num_envs 2048 --robot g1 --headless
```

**Before (carb logging)**
[INFO]: App start time: 4676.57 ms
[INFO]: Imports time: 2008.77 ms
[INFO]: Scene creation time: 2966.36 ms
[INFO]: Sim start time: 5782.76 ms
[INFO]: Per step time: 15.80 ms

**After (omni.log logging)**
[INFO]: App start time: 4833.56 ms
[INFO]: Imports time: 1983.67 ms
[INFO]: Scene creation time: 2792.97 ms
[INFO]: Sim start time: 5805.97 ms
[INFO]: Per step time: 15.86 ms


## 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
- [ ] 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 94f46109
......@@ -13,8 +13,8 @@ from collections.abc import Sequence
from prettytable import PrettyTable
from typing import TYPE_CHECKING
import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.log
import omni.physics.tensors.impl.api as physx
from omni.isaac.core.utils.types import ArticulationActions
from pxr import PhysxSchema, UsdPhysics
......@@ -542,7 +542,7 @@ class Articulation(AssetBase):
# update default joint pos to stay within the new limits
if torch.any((self._data.default_joint_pos < limits[..., 0]) | (self._data.default_joint_pos > limits[..., 1])):
self._data.default_joint_pos = torch.clamp(self._data.default_joint_pos, limits[..., 0], limits[..., 1])
carb.log_warn(
omni.log.warn(
"Some default joint positions are outside of the range of the new joint limits. Default joint positions"
" will be clamped to be within the new joint limits."
)
......@@ -925,13 +925,13 @@ class Articulation(AssetBase):
raise RuntimeError(f"Failed to create articulation at: {self.cfg.prim_path}. Please check PhysX logs.")
# log information about the articulation
carb.log_info(f"Articulation initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
carb.log_info(f"Is fixed root: {self.is_fixed_base}")
carb.log_info(f"Number of bodies: {self.num_bodies}")
carb.log_info(f"Body names: {self.body_names}")
carb.log_info(f"Number of joints: {self.num_joints}")
carb.log_info(f"Joint names: {self.joint_names}")
carb.log_info(f"Number of fixed tendons: {self.num_fixed_tendons}")
omni.log.info(f"Articulation initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
omni.log.info(f"Is fixed root: {self.is_fixed_base}")
omni.log.info(f"Number of bodies: {self.num_bodies}")
omni.log.info(f"Body names: {self.body_names}")
omni.log.info(f"Number of joints: {self.num_joints}")
omni.log.info(f"Joint names: {self.joint_names}")
omni.log.info(f"Number of fixed tendons: {self.num_fixed_tendons}")
# container for data access
self._data = ArticulationData(self.root_physx_view, self.device)
......@@ -1142,7 +1142,7 @@ class Articulation(AssetBase):
velocity_limit=usd_velocity_limit[:, joint_ids],
)
# log information on actuator groups
carb.log_info(
omni.log.info(
f"Actuator collection: {actuator_name} with model '{actuator_cfg.class_type.__name__}' and"
f" joint names: {joint_names} [{joint_ids}]."
)
......@@ -1177,7 +1177,7 @@ class Articulation(AssetBase):
# perform some sanity checks to ensure actuators are prepared correctly
total_act_joints = sum(actuator.num_joints for actuator in self.actuators.values())
if total_act_joints != (self.num_joints - self.num_fixed_tendons):
carb.log_warn(
omni.log.warn(
"Not all actuators are configured! Total number of actuated joints not equal to number of"
f" joints available: {total_act_joints} != {self.num_joints - self.num_fixed_tendons}."
)
......@@ -1336,7 +1336,7 @@ class Articulation(AssetBase):
effort_limits[index],
])
# convert table to string
carb.log_info(f"Simulation parameters for joints in {self.cfg.prim_path}:\n" + table.get_string())
omni.log.info(f"Simulation parameters for joints in {self.cfg.prim_path}:\n" + table.get_string())
# read out all tendon parameters from simulation
if self.num_fixed_tendons > 0:
......@@ -1372,4 +1372,4 @@ class Articulation(AssetBase):
ft_offsets[index],
])
# convert table to string
carb.log_info(f"Simulation parameters for tendons in {self.cfg.prim_path}:\n" + tendon_table.get_string())
omni.log.info(f"Simulation parameters for tendons in {self.cfg.prim_path}:\n" + tendon_table.get_string())
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.physics.tensors.impl.api as physx
from pxr import PhysxSchema, UsdShade
......@@ -305,7 +305,7 @@ class DeformableObject(AssetBase):
material_prim = mat_prim
break
if material_prim is None:
carb.log_info(
omni.log.info(
f"Failed to find a deformable material binding for '{root_prim.GetPath().pathString}'."
" The material properties will be set to default values and are not modifiable at runtime."
" If you want to modify the material properties, please ensure that the material is bound"
......@@ -341,14 +341,14 @@ class DeformableObject(AssetBase):
self._material_physx_view = None
# log information about the deformable body
carb.log_info(f"Deformable body initialized at: {root_prim_path_expr}")
carb.log_info(f"Number of instances: {self.num_instances}")
carb.log_info(f"Number of bodies: {self.num_bodies}")
omni.log.info(f"Deformable body initialized at: {root_prim_path_expr}")
omni.log.info(f"Number of instances: {self.num_instances}")
omni.log.info(f"Number of bodies: {self.num_bodies}")
if self._material_physx_view is not None:
carb.log_info(f"Deformable material initialized at: {material_prim_path_expr}")
carb.log_info(f"Number of instances: {self._material_physx_view.count}")
omni.log.info(f"Deformable material initialized at: {material_prim_path_expr}")
omni.log.info(f"Number of instances: {self._material_physx_view.count}")
else:
carb.log_info("No deformable material found. Material properties will be set to default values.")
omni.log.info("No deformable material found. Material properties will be set to default values.")
# container for data access
self._data = DeformableObjectData(self.root_physx_view, self.device)
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.physics.tensors.impl.api as physx
from pxr import UsdPhysics
......@@ -299,10 +299,10 @@ class RigidObject(AssetBase):
raise RuntimeError(f"Failed to create rigid body at: {self.cfg.prim_path}. Please check PhysX logs.")
# log information about the rigid body
carb.log_info(f"Rigid body initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
carb.log_info(f"Number of instances: {self.num_instances}")
carb.log_info(f"Number of bodies: {self.num_bodies}")
carb.log_info(f"Body names: {self.body_names}")
omni.log.info(f"Rigid body initialized at: {self.cfg.prim_path} with root '{root_prim_path_expr}'.")
omni.log.info(f"Number of instances: {self.num_instances}")
omni.log.info(f"Number of bodies: {self.num_bodies}")
omni.log.info(f"Body names: {self.body_names}")
# container for data access
self._data = RigidObjectData(self.root_physx_view, self.device)
......
......@@ -16,9 +16,9 @@ from abc import abstractmethod
from collections.abc import Sequence
from typing import Any, ClassVar
import carb
import omni.isaac.core.utils.torch as torch_utils
import omni.kit.app
import omni.log
from omni.isaac.version import get_version
from omni.isaac.lab.managers import EventManager
......@@ -83,7 +83,7 @@ class DirectMARLEnv:
if self.cfg.seed is not None:
self.cfg.seed = self.seed(self.cfg.seed)
else:
carb.log_warn("Seed not set for the environment. The environment creation may not be deterministic.")
omni.log.warn("Seed not set for the environment. The environment creation may not be deterministic.")
# create a simulation context to control the simulator
if SimulationContext.instance() is None:
......@@ -105,7 +105,7 @@ class DirectMARLEnv:
f"({self.cfg.decimation}). Multiple multiple render calls will happen for each environment step."
"If this is not intended, set the render interval to be equal to the decimation."
)
carb.log_warn(msg)
omni.log.warn(msg)
# generate scene
with Timer("[INFO]: Time taken for scene creation", "scene_creation"):
......
......@@ -16,9 +16,9 @@ from abc import abstractmethod
from collections.abc import Sequence
from typing import Any, ClassVar
import carb
import omni.isaac.core.utils.torch as torch_utils
import omni.kit.app
import omni.log
from omni.isaac.version import get_version
from omni.isaac.lab.managers import EventManager
......@@ -88,7 +88,7 @@ class DirectRLEnv(gym.Env):
if self.cfg.seed is not None:
self.cfg.seed = self.seed(self.cfg.seed)
else:
carb.log_warn("Seed not set for the environment. The environment creation may not be deterministic.")
omni.log.warn("Seed not set for the environment. The environment creation may not be deterministic.")
# create a simulation context to control the simulator
if SimulationContext.instance() is None:
......@@ -110,7 +110,7 @@ class DirectRLEnv(gym.Env):
f"({self.cfg.decimation}). Multiple multiple render calls will happen for each environment step."
"If this is not intended, set the render interval to be equal to the decimation."
)
carb.log_warn(msg)
omni.log.warn(msg)
# generate scene
with Timer("[INFO]: Time taken for scene creation", "scene_creation"):
......
......@@ -8,8 +8,8 @@ import torch
from collections.abc import Sequence
from typing import Any
import carb
import omni.isaac.core.utils.torch as torch_utils
import omni.log
from omni.isaac.lab.managers import ActionManager, EventManager, ObservationManager
from omni.isaac.lab.scene import InteractiveScene
......@@ -78,7 +78,7 @@ class ManagerBasedEnv:
if self.cfg.seed is not None:
self.cfg.seed = self.seed(self.cfg.seed)
else:
carb.log_warn("Seed not set for the environment. The environment creation may not be deterministic.")
omni.log.warn("Seed not set for the environment. The environment creation may not be deterministic.")
# create a simulation context to control the simulator
if SimulationContext.instance() is None:
......@@ -106,7 +106,7 @@ class ManagerBasedEnv:
f"({self.cfg.decimation}). Multiple multiple render calls will happen for each environment step. "
"If this is not intended, set the render interval to be equal to the decimation."
)
carb.log_warn(msg)
omni.log.warn(msg)
# counter for simulation steps
self._sim_step_counter = 0
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.assets.articulation import Articulation
......@@ -52,7 +52,7 @@ class BinaryJointAction(ActionTerm):
self._joint_ids, self._joint_names = self._asset.find_joints(self.cfg.joint_names)
self._num_joints = len(self._joint_ids)
# log the resolved joint names for debugging
carb.log_info(
omni.log.info(
f"Resolved joint names for the action term {self.__class__.__name__}:"
f" {self._joint_names} [{self._joint_ids}]"
)
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.assets.articulation import Articulation
......@@ -61,7 +61,7 @@ class JointAction(ActionTerm):
)
self._num_joints = len(self._joint_ids)
# log the resolved joint names for debugging
carb.log_info(
omni.log.info(
f"Resolved joint names for the action term {self.__class__.__name__}:"
f" {self._joint_names} [{self._joint_ids}]"
)
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.isaac.lab.utils.math as math_utils
import omni.isaac.lab.utils.string as string_utils
......@@ -53,7 +53,7 @@ class JointPositionToLimitsAction(ActionTerm):
self._joint_ids, self._joint_names = self._asset.find_joints(self.cfg.joint_names)
self._num_joints = len(self._joint_ids)
# log the resolved joint names for debugging
carb.log_info(
omni.log.info(
f"Resolved joint names for the action term {self.__class__.__name__}:"
f" {self._joint_names} [{self._joint_ids}]"
)
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
from omni.isaac.lab.assets.articulation import Articulation
from omni.isaac.lab.managers.action_manager import ActionTerm
......@@ -88,11 +88,11 @@ class NonHolonomicAction(ActionTerm):
self._joint_ids = [x_joint_id[0], y_joint_id[0], yaw_joint_id[0]]
self._joint_names = [x_joint_name[0], y_joint_name[0], yaw_joint_name[0]]
# log info for debugging
carb.log_info(
omni.log.info(
f"Resolved joint names for the action term {self.__class__.__name__}:"
f" {self._joint_names} [{self._joint_ids}]"
)
carb.log_info(
omni.log.info(
f"Resolved body name for the action term {self.__class__.__name__}: {self._body_name} [{self._body_idx}]"
)
......
......@@ -9,7 +9,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.isaac.lab.utils.math as math_utils
from omni.isaac.lab.assets.articulation import Articulation
......@@ -70,11 +70,11 @@ class DifferentialInverseKinematicsAction(ActionTerm):
self._jacobi_joint_ids = [i + 6 for i in self._joint_ids]
# log info for debugging
carb.log_info(
omni.log.info(
f"Resolved joint names for the action term {self.__class__.__name__}:"
f" {self._joint_names} [{self._joint_ids}]"
)
carb.log_info(
omni.log.info(
f"Resolved body name for the action term {self.__class__.__name__}: {self._body_name} [{self._body_idx}]"
)
# Avoid indexing across all joints for efficiency
......
......@@ -12,7 +12,7 @@ from collections.abc import Sequence
from prettytable import PrettyTable
from typing import TYPE_CHECKING
import carb
import omni.log
from .manager_base import ManagerBase, ManagerTermBase
from .manager_term_cfg import EventTermCfg
......@@ -157,7 +157,7 @@ class EventManager(ManagerBase):
"""
# check if mode is valid
if mode not in self._mode_term_names:
carb.log_warn(f"Event mode '{mode}' is not defined. Skipping event.")
omni.log.warn(f"Event mode '{mode}' is not defined. Skipping event.")
return
# check if mode is interval and dt is not provided
if mode == "interval" and dt is None:
......@@ -324,7 +324,7 @@ class EventManager(ManagerBase):
)
if term_cfg.mode != "reset" and term_cfg.min_step_count_between_reset != 0:
carb.log_warn(
omni.log.warn(
f"Event term '{term_name}' has 'min_step_count_between_reset' set to a non-zero value"
" but the mode is not 'reset'. Ignoring the 'min_step_count_between_reset' value."
)
......
......@@ -11,7 +11,7 @@ from abc import ABC, abstractmethod
from collections.abc import Sequence
from typing import TYPE_CHECKING, Any
import carb
import omni.log
import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.utils import string_to_callable
......@@ -251,7 +251,7 @@ class ManagerBase(ABC):
if value.body_ids is not None:
msg += f"\n\tBody names: {value.body_names} [{value.body_ids}]"
# print the information
carb.log_info(msg)
omni.log.info(msg)
# store the entity
term_cfg.params[key] = value
......
......@@ -171,7 +171,7 @@ class InteractiveScene:
carb_settings_iface = carb.settings.get_settings()
has_multi_assets = carb_settings_iface.get("/isaaclab/spawn/multi_assets")
if has_multi_assets and self.cfg.replicate_physics:
carb.log_warn(
omni.log.warn(
"Varying assets might have been spawned under different environments."
" However, the replicate physics flag is enabled in the 'InteractiveScene' configuration."
" This may adversely affect PhysX parsing. We recommend disabling this property."
......@@ -239,7 +239,7 @@ class InteractiveScene:
for prim in self.stage.Traverse():
if prim.HasAPI(PhysxSchema.PhysxSceneAPI):
self._physics_scene_path = prim.GetPrimPath().pathString
carb.log_info(f"Physics scene prim path: {self._physics_scene_path}")
omni.log.info(f"Physics scene prim path: {self._physics_scene_path}")
break
if self._physics_scene_path is None:
raise RuntimeError("No physics scene found! Please make sure one exists.")
......
......@@ -251,7 +251,7 @@ class Camera(SensorBase):
# TODO: Adjust to handle aperture offsets once supported by omniverse
# Internal ticket from rendering team: OM-42611
if params["horizontal_aperture_offset"] > 1e-4 or params["vertical_aperture_offset"] > 1e-4:
carb.log_warn("Camera aperture offsets are not supported by Omniverse. These parameters are ignored.")
omni.log.warn("Camera aperture offsets are not supported by Omniverse. These parameters are ignored.")
# change data for corresponding camera index
sensor_prim = self._sensor_prims[i]
......
......@@ -10,7 +10,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING
import carb
import omni.log
import omni.physics.tensors.impl.api as physx
from pxr import UsdPhysics
......@@ -114,10 +114,10 @@ class FrameTransformer(SensorBase):
self._apply_source_frame_offset = True
# Handle source frame offsets
if is_identity_pose(source_frame_offset_pos, source_frame_offset_quat):
carb.log_verbose(f"No offset application needed for source frame as it is identity: {self.cfg.prim_path}")
omni.log.verbose(f"No offset application needed for source frame as it is identity: {self.cfg.prim_path}")
self._apply_source_frame_offset = False
else:
carb.log_verbose(f"Applying offset to source frame as it is not identity: {self.cfg.prim_path}")
omni.log.verbose(f"Applying offset to source frame as it is not identity: {self.cfg.prim_path}")
# Store offsets as tensors (duplicating each env's offsets for ease of multiplication later)
self._source_frame_offset_pos = source_frame_offset_pos.unsqueeze(0).repeat(self._num_envs, 1)
self._source_frame_offset_quat = source_frame_offset_quat.unsqueeze(0).repeat(self._num_envs, 1)
......@@ -194,12 +194,12 @@ class FrameTransformer(SensorBase):
target_offsets[frame_name] = {"pos": offset_pos, "quat": offset_quat}
if not self._apply_target_frame_offset:
carb.log_info(
omni.log.info(
f"No offsets application needed from '{self.cfg.prim_path}' to target frames as all"
f" are identity: {frames[1:]}"
)
else:
carb.log_info(
omni.log.info(
f"Offsets application needed from '{self.cfg.prim_path}' to the following target frames:"
f" {non_identity_offset_frames}"
)
......
......@@ -11,7 +11,7 @@ import torch
from collections.abc import Sequence
from typing import TYPE_CHECKING, ClassVar
import carb
import omni.log
import omni.physics.tensors.impl.api as physx
import warp as wp
from omni.isaac.core.prims import XFormPrimView
......@@ -144,7 +144,7 @@ class RayCaster(SensorBase):
else:
self._view = XFormPrimView(self.cfg.prim_path, reset_xform_properties=False)
found_supported_prim_class = True
carb.log_warn(f"The prim at path {prim.GetPath().pathString} is not a physics prim! Using XFormPrimView.")
omni.log.warn(f"The prim at path {prim.GetPath().pathString} is not a physics prim! Using XFormPrimView.")
# check if prim view class is found
if not found_supported_prim_class:
raise RuntimeError(f"Failed to find a valid prim view class for the prim paths: {self.cfg.prim_path}")
......@@ -188,14 +188,14 @@ class RayCaster(SensorBase):
indices = np.asarray(mesh_prim.GetFaceVertexIndicesAttr().Get())
wp_mesh = convert_to_warp_mesh(points, indices, device=self.device)
# print info
carb.log_info(
omni.log.info(
f"Read mesh prim: {mesh_prim.GetPath()} with {len(points)} vertices and {len(indices)} faces."
)
else:
mesh = make_plane(size=(2e6, 2e6), height=0.0, center_zero=True)
wp_mesh = convert_to_warp_mesh(mesh.vertices, mesh.faces, device=self.device)
# print info
carb.log_info(f"Created infinite plane mesh prim: {mesh_prim.GetPath()}.")
omni.log.info(f"Created infinite plane mesh prim: {mesh_prim.GetPath()}.")
# add the warp mesh to the list
RayCaster.meshes[mesh_prim_path] = wp_mesh
......
......@@ -6,8 +6,8 @@
# needed to import for allowing type-hinting: Usd.Stage | None
from __future__ import annotations
import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.log
import omni.physx.scripts.utils as physx_utils
from omni.physx.scripts import deformableUtils as deformable_utils
from pxr import PhysxSchema, Usd, UsdPhysics
......@@ -131,12 +131,12 @@ def modify_articulation_root_properties(
# if we found a fixed joint, enable/disable it based on the input
# otherwise, create a fixed joint between the world and the root link
if existing_fixed_joint_prim is not None:
carb.log_info(
omni.log.info(
f"Found an existing fixed joint for the articulation: '{prim_path}'. Setting it to: {fix_root_link}."
)
existing_fixed_joint_prim.GetJointEnabledAttr().Set(fix_root_link)
elif fix_root_link:
carb.log_info(f"Creating a fixed joint for the articulation: '{prim_path}'.")
omni.log.info(f"Creating a fixed joint for the articulation: '{prim_path}'.")
# note: we have to assume that the root prim is a rigid body,
# i.e. we don't handle the case where the root prim is not a rigid body but has articulation api on it
......@@ -500,10 +500,10 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd.
rb.CreateSleepThresholdAttr().Set(0.0)
# add contact report API with threshold of zero
if not child_prim.HasAPI(PhysxSchema.PhysxContactReportAPI):
carb.log_verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'")
omni.log.verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'")
cr_api = PhysxSchema.PhysxContactReportAPI.Apply(child_prim)
else:
carb.log_verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'")
omni.log.verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'")
cr_api = PhysxSchema.PhysxContactReportAPI.Get(stage, child_prim.GetPrimPath())
# set threshold to zero
cr_api.CreateThresholdAttr().Set(threshold)
......
......@@ -16,6 +16,7 @@ from typing import Any
import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.log
import omni.physx
from omni.isaac.core.simulation_context import SimulationContext as _SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
......@@ -338,7 +339,7 @@ class SimulationContext(_SimulationContext):
"""
# check if mode change is possible -- not possible when no GUI is available
if not self._has_gui:
carb.log_warn(
omni.log.warn(
f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}."
)
return
......@@ -616,7 +617,7 @@ class SimulationContext(_SimulationContext):
if event.type == int(omni.timeline.TimelineEventType.STOP):
# keep running the simulator when configured to not shutdown the app
if self._has_gui and sys.exc_info()[0] is None:
carb.log_warn(
omni.log.warn(
"Simulation is stopped. The app will keep running with physics disabled."
" Press Ctrl+C or close the window to exit the app."
)
......@@ -760,7 +761,7 @@ def build_simulation_context(
yield sim
except Exception:
carb.log_error(traceback.format_exc())
omni.log.error(traceback.format_exc())
raise
finally:
if not sim.has_gui():
......
......@@ -7,10 +7,10 @@ from __future__ import annotations
from typing import TYPE_CHECKING
import carb
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.kit.commands
import omni.log
from pxr import Gf, Sdf, Usd
from omni.isaac.lab.sim import converters, schemas
......@@ -226,7 +226,7 @@ def _spawn_from_usd_file(
scale=cfg.scale,
)
else:
carb.log_warn(f"A prim already exists at prim path: '{prim_path}'.")
omni.log.warn(f"A prim already exists at prim path: '{prim_path}'.")
# modify variants
if hasattr(cfg, "variants") and cfg.variants is not None:
......
......@@ -7,9 +7,9 @@ from __future__ import annotations
from typing import TYPE_CHECKING
import carb
import omni.isaac.core.utils.prims as prim_utils
import omni.kit.commands
import omni.log
from pxr import Sdf, Usd
from omni.isaac.lab.sim.utils import clone
......@@ -104,7 +104,7 @@ def spawn_camera(
# TODO: Adjust to handle aperture offsets once supported by omniverse
# Internal ticket from rendering team: OM-42611
if cfg.horizontal_aperture_offset > 1e-4 or cfg.vertical_aperture_offset > 1e-4:
carb.log_warn("Camera aperture offsets are not supported by Omniverse. These parameters will be ignored.")
omni.log.warn("Camera aperture offsets are not supported by Omniverse. These parameters will be ignored.")
# custom attributes in the config that are not USD Camera parameters
non_usd_cfg_param_names = [
......
......@@ -13,9 +13,9 @@ import re
from collections.abc import Callable
from typing import TYPE_CHECKING, Any
import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.kit.commands
import omni.log
from omni.isaac.cloner import Cloner
from pxr import PhysxSchema, Sdf, Usd, UsdGeom, UsdPhysics, UsdShade
......@@ -70,7 +70,7 @@ def safe_set_attribute_on_usd_schema(schema_api: Usd.APISchemaBase, name: str, v
else:
# think: do we ever need to create the attribute if it doesn't exist?
# currently, we are not doing this since the schemas are already created with some defaults.
carb.log_error(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.")
omni.log.error(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.")
raise TypeError(f"Attribute '{attr_name}' does not exist on prim '{schema_api.GetPath()}'.")
......@@ -189,7 +189,7 @@ def apply_nested(func: Callable) -> Callable:
count_success += 1
# check if we were successful in applying the function to any prim
if count_success == 0:
carb.log_warn(
omni.log.warn(
f"Could not perform '{func.__name__}' on any prims under: '{prim_path}'."
" This might be because of the following reasons:"
"\n\t(1) The desired attribute does not exist on any of the prims."
......@@ -391,7 +391,7 @@ def bind_physics_material(
has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI)
has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem)
if not (has_physics_scene_api or has_collider or has_deformable_body or has_particle_system):
carb.log_verbose(
omni.log.verbose(
f"Cannot apply physics material '{material_path}' on prim '{prim_path}'. It is neither a"
" PhysX scene, collider, a deformable body, nor a particle system."
)
......@@ -851,14 +851,14 @@ def select_usd_variants(prim_path: str, variants: object | dict[str, str], stage
for variant_set_name, variant_selection in variants.items():
# Check if the variant set exists on the prim.
if not existing_variant_sets.HasVariantSet(variant_set_name):
carb.log_warn(f"Variant set '{variant_set_name}' does not exist on prim '{prim_path}'.")
omni.log.warn(f"Variant set '{variant_set_name}' does not exist on prim '{prim_path}'.")
continue
variant_set = existing_variant_sets.GetVariantSet(variant_set_name)
# Only set the variant selection if it is different from the current selection.
if variant_set.GetVariantSelection() != variant_selection:
variant_set.SetVariantSelection(variant_selection)
carb.log_info(
omni.log.info(
f"Setting variant selection '{variant_selection}' for variant set '{variant_set_name}' on"
f" prim '{prim_path}'."
)
......@@ -8,7 +8,7 @@ import os
import torch
import trimesh
import carb
import omni.log
from omni.isaac.lab.utils.dict import dict_to_md5_hash
from omni.isaac.lab.utils.io import dump_yaml
......@@ -119,7 +119,7 @@ class TerrainGenerator:
# throw a warning if the cache is enabled but the seed is not set
if self.cfg.use_cache and self.cfg.seed is None:
carb.log_warn(
omni.log.warn(
"Cache is enabled but the seed is not set. The terrain generation will not be reproducible."
" Please set the seed in the terrain generator configuration to make the generation reproducible."
)
......@@ -295,7 +295,7 @@ class TerrainGenerator:
"""
# sample flat patches if specified
if sub_terrain_cfg.flat_patch_sampling is not None:
carb.log_info(f"Sampling flat patches for sub-terrain at (row, col): ({row}, {col})")
omni.log.info(f"Sampling flat patches for sub-terrain at (row, col): ({row}, {col})")
# convert the mesh to warp mesh
wp_mesh = convert_to_warp_mesh(mesh.vertices, mesh.faces, device=self.device)
# sample flat patches based on each patch configuration for that sub-terrain
......
......@@ -32,11 +32,11 @@ simulation_app = SimulationApp({"headless": args_cli.headless})
import torch
import carb
import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.kit.commands
import omni.log
import omni.physx
from omni.isaac.core.articulations import ArticulationView
from omni.isaac.core.utils.carb import set_carb_setting
......@@ -50,7 +50,7 @@ if nucleus_utils.get_assets_root_path() is None:
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
carb.log_error(msg)
omni.log.error(msg)
raise RuntimeError(msg)
......
......@@ -43,7 +43,7 @@ simulation_app = SimulationApp({"headless": args_cli.headless})
import os
import torch
import carb
import omni.log
try:
import omni.isaac.nucleus as nucleus_utils
......@@ -62,7 +62,7 @@ if nucleus_utils.get_assets_root_path() is None:
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
carb.log_error(msg)
omni.log.error(msg)
raise RuntimeError(msg)
......
......@@ -37,7 +37,7 @@ import ctypes
import gc
import torch # noqa: F401
import carb
import omni.log
try:
import omni.isaac.nucleus as nucleus_utils
......@@ -55,7 +55,7 @@ if nucleus_utils.get_assets_root_path() is None:
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
carb.log_error(msg)
omni.log.error(msg)
raise RuntimeError(msg)
......
......@@ -15,7 +15,7 @@ import os
import torch
from collections.abc import Iterable
import carb
import omni.log
class RobomimicDataCollector:
......@@ -148,10 +148,10 @@ class RobomimicDataCollector:
"""
# check if data should be recorded
if self._is_first_interaction:
carb.log_warn("Please call reset before adding new data. Calling reset...")
omni.log.warn("Please call reset before adding new data. Calling reset...")
self.reset()
if self._is_stop:
carb.log_warn(f"Desired number of demonstrations collected: {self._demo_count} >= {self._num_demos}.")
omni.log.warn(f"Desired number of demonstrations collected: {self._demo_count} >= {self._num_demos}.")
return
# check datatype
if isinstance(value, torch.Tensor):
......@@ -192,7 +192,7 @@ class RobomimicDataCollector:
"""
# check that data is being recorded
if self._h5_file_stream is None or self._h5_data_group is None:
carb.log_error("No file stream has been opened. Please call reset before flushing data.")
omni.log.error("No file stream has been opened. Please call reset before flushing data.")
return
# iterate over each environment and add their data
......
......@@ -40,10 +40,8 @@ simulation_app = app_launcher.app
import gymnasium as gym
import torch
import traceback
from collections.abc import Sequence
import carb
import warp as wp
from omni.isaac.lab.sensors import FrameTransformer
......@@ -313,13 +311,7 @@ def main():
if __name__ == "__main__":
try:
# run the main execution
main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
# run the main execution
main()
# close sim app
simulation_app.close()
......@@ -35,7 +35,7 @@ simulation_app = app_launcher.app
import gymnasium as gym
import torch
import carb
import omni.log
from omni.isaac.lab.devices import Se3Gamepad, Se3Keyboard, Se3SpaceMouse
from omni.isaac.lab.managers import TerminationTermCfg as DoneTerm
......@@ -77,7 +77,7 @@ def main():
env = gym.make(args_cli.task, cfg=env_cfg)
# check environment name (for reach , we don't allow the gripper)
if "Reach" in args_cli.task:
carb.log_warn(
omni.log.warn(
f"The environment '{args_cli.task}' does not support gripper control. The device command will be ignored."
)
......
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