2023.1.1

Highlights

  • General

    • Kit SDK 105.1.2

    • WebSocket live-streaming will be removed in the next version of Isaac Sim

    • Replicator Composer will be removed in the next version of Isaac Sim

    • omni.isaac.synthetic_utils will be removed in the next version of Isaac Sim in favor of omni.replicator

    • omni.isaac.shapenet will be removed in the next version of Isaac Sim

    • omni.isaac.urdf will be removed in the next version of Isaac Sim in favor of omni.importer.urdf

    • Fixes for security vulnerabilities: CVE-2023-49083

    • Added collider compatibility table

    • Added Joint gains tuning guide

  • New Robots
    • Added Franka Research 3 (FR3) manipulator

    • Renamed Carter V24 to Nova Carter

  • Sensors
    • RTX Lidar has corrected some outputs, including objectId, velocity and hitPointNormal

  • Isaac Core
    • Fix for USD joint sign convention used in joint limits, joint target positions/velocities, joint forces, etc;

      • If the arrangement of USD joint bodies (body0/body1) isn’t similar to the underlying physics kinematic tree hierarchy (parent/child), scalar properties undergo a sign inversion. Notably, for joint forces, a transformation is applied to ensure reporting in the USD joint body1 frame.

      • It is important to note that this adjustment may impact the behavior of existing user assets, particularly in cases where warnings related to the incorrect ordering of USD joint bodies have been overlooked.

    • Added get_assets_root_path_async()

    • Added On Physics Step node

  • ROS
    • Added ROS1 and ROS2 AckermannDriveStamped publisher and subscriber nodes

    • New ROS1/ROS2 Clock publisher and subscriber tutorials

  • Replicator
    • Added DataVisualizationWriter example writer to omni.replicator.isaac to write labeled annotator data to disk

    • Added custom event trigger example to Replicator → Useful Snippets

  • Gym
    • Added support for viewport recording during training/inferencing using gym wrapper class RecordVideo

    • Added video tutorial for extension workflow

    • Minor bug fixes and cleanup in OmniIsaacGymEnvs

  • Metro Sim (People, ORC, ORO)
    • First release of the Omni.Replicator.Character extension suite.

      • Designed to generate synthetic data across a variety of environments. It provides controls over environments, cameras, agents through the use of configuration and command files.

    • First release of the omni.replicator.object extension.

      • Description file based object simulation. Cameras, lights and geometry are defined as mutables that randomize per frame, while harmonizers are defined to coordinate randomization, and settings are supported to configure the simulation enviroment.

      • Added
        • Bin pack harmonizer. When using it to harmonize a transform operator, users can pack a group of objects to a cuboid with user-specified size.

        • Mutable shader attributes for a geometry. This is a mutable attribute that allows mutation of shader attributes, e.g. texture rotations.

        • Setting to exclude occluded objects by a threshold.

        • Tutorial/test USD models.

      • Fixed
        • Support for concave objects in container.

Extensions

  • omni.exporter.urdf

    • Added

      • Exporting sensor prim frames to URDF

      • Ability to set mesh path prefix

      • Optionally setting output to directory (URDF file name automatically set to match USD file name)

    • Fixed

      • Scaling bug when geometry prim is a child of Xform prim with scaling

      • Cylinder scaling issue

      • Joint frame alignment when child link transform is not identity

      • Exporting revolute joints with inf limits, export as continuous joints now

      • Too many root links

      • Velocity and effort limits always being set to zero

      • Large camera meshes added erroneously to URDF

      • Terminal output labeled as error even when export is successful

  • omni.isaac.asset_browser

    • Changed

      • Fix missing default icon

      • Update based on omni.kit.browser.asset-1.3.7

      • Update asset paths to 2023.1.1

  • omni.isaac.assets_check

    • Changed

      • Use get_assets_root_path_async()

  • omni.isaac.cloner

    • Fixed

      • Fixed error with GridCloner when offsets are passed

      • Add test case with position and orientation offsets for GridCloner

      • Fixed the order in which xformop is set while cloning. Earlier a set was passed instead of list.

  • omni.isaac.conveyor

    • Fixed

      • Error when Node starts for the first time if it doesn’t have a Texture translate attribute.

  • omni.isaac.core

    • Added

      • set_block_on_render and get_block_on_render to control waitIdle flag

      • added rot_matrices_to_quats method to torch utils

      • test for get_joint_position in test_articulation to catch the sign switch that happens when articulation joints have different body0 and body1 than expected.

    • Changed

      • Add more articulation metadata

      • Fix contact reporter API schema

      • Fix joint limits

      • Add examples to docstrings, fix type annotations, and improve description. Affected modules: omni.isaac.core.world (world) and omni.isaac.core.simulation_context (simulation_context)

      • Add get_assets_root_path_async()

      • Add get_full_asset_path_async()

      • Add get_server_path_async()

      • /app/runLoops/main/rateLimitEnabled in standalone workflow will be set to False

      • Apply codespell to fix common misspellings and typos

      • Add examples to docstrings, fix type annotations, and improve description. Affected modules: omni.isaac.core.objects (capsule, cone, cuboid, cylinder, sphere, ground_plane)

      • Add examples to docstrings, fix type annotations, and improve description. Affected modules: omni.isaac.core.prims (xform_prim, xform_prim_view, rigid_prim, rigid_prim_view, rigid_contact_view, geometry_prim, geometry_prim_view, base_sensor)

      • Add examples to docstrings, fix type annotations, and improve description. Affected modules: omni.isaac.core.articulations (articulation, articulation_view) and omni.isaac.core.robots (robot, robot_view)

      • Removed create_hydra_texture; use rep.create.render_product from omni.replicator.core instead.

      • Add examples to docstrings, fix type annotations, and improve description. Affected modules: omni.isaac.core.utils (bounds, carb, constants, extension, mesh, physics, prim, stage)

      • Update asset paths to 2023.1.1

    • Fixed

      • set_live_sync method

      • quats_to_rot_matrices under torch utils to handle 1 dimensional input and batched

      • pad method under torch utils

      • Forward the density parameter to the RigidPrimView instance in RigidPrim class constructor

      • Fix argument typo when applying a physics material to a ground plane object

      • Add missing worker thread parsing from sim config

      • Fix indices used to set the GeometryPrimView collision API properties

      • Fix the indices comparison that prevented applying several physical materials to a GeometryPrimView object

      • Use articulation view metadata to get DOF types given specific DOF names

      • Remove unexpected keyword argument when printing the stage via the stage utils

      • renamed utils.torch.rotations quat_to_rot_matrices to quats_to_rot_matrices to be consistent with numpy, originally named function is now a redirect function

  • omni.isaac.core_nodes

    • Added

      • On Physics Step Node

    • Fixed

      • Annotator unit test due to replicator update

  • omni.isaac.debug_draw

    • Added

      • Check for valid prim path, so the debug drawing nodes will issue an error instead of crash with invalid path

  • omni.isaac.dofbot

    • Changed

      • switched gripper deltas them because of a change in physX regarding flipped signs.

  • omni.isaac.dynamic_control

    • Fixed

      • Issue with prim getting removed at random

  • omni.isaac.examples

    • Changed

      • Force stop bin filling once gripper constraint breaks

      • Add small force to induce gripper breaking if it doesn’t happen on bin pieces falling

      • Increase quadruped example physics rate to 400hz

    • Fixed

      • Fixed issue with screwing in nut and bolt demo

      • Improved accuracy of placement and rotation and increased rotation speed

      • Moved nut screwing to start with 3rd nut with slight improvement to centering

  • omni.isaac.gym

    • Added

      • Add APIs for recording viewport during training

    • Changed

      • Improve test coverage

      • Update outdated MT tests to use extension workflow

  • omni.isaac.kit

    • Changed

      • Set /app/player/useFixedTimeStepping to False since the loop runner controls stepping

    • Fixed

      • set_live_sync method

  • omni.isaac.motion_generation

    • Added

      • Add RMPflow configs for FR3 robot

    • Changed

      • Moved wheel base pose controller to wheeled robots extension

  • omni.isaac.occupancy_map

    • Fixed

      • Updated api docs to mention correct return types.

  • omni.isaac.ocs2

    • Changed

      • Disable tests in docker

  • omni.isaac.quadruped

    • Changed

      • Added torque clamp to the quadruped control in response to physics change

      • Behavior changed, investigating performance issue

    • Fixed

      • Add the missing import statement for the IMUSensor

  • omni.isaac.range_sensor

    • Fixed

      • Issue where ReadLidar nodes ticking twice on the same set of data if run twice per frame

  • omni.isaac.robot_assembler

    • Fixed

      • Fixed breaking test cases that loaded local USD assets with references to robots on Nucleus

  • omni.isaac.ros2_bridge

    • Added

      • ROS2 Ackermann Subscriber and Publisher nodes using non-default ROS2 AckermannDriveStamped message type.

      • Option to publish a full scan from RTX lidar

      • APIs to dynamically load ROS2 libraries at runtime depending on what messages are being created. Will only be used for select non-default ROS 2 messages.

    • Fixed

      • Removed conflicting TF Publishers from standalone ROS2 Moveit tutorial

      • Queue Size (QOS depth) settings now enforced when creating subscriber nodes.

      • Added unit tests for variable queue sizes in subscribers

  • omni.isaac.ros_bridge

    • Added

      • ROS1 Ackermann Subscriber and Publisher nodes

      • Option to publish a full scan from RTX lidar

  • omni.isaac.sensor

    • Added

      • ZED X sensor to menu item

    • Changed

      • IsaacCreateRTXLidarScanBuffer transformPoints defaults to false

      • RtxSensorCpuIsaacCreateRTXLidarScanBuffer doTransform defaults to true

    • Fixed

      • Issue where ReadLidar nodes ticking twice on the same set of data if run twice per frame

      • aperture setters and getters in Camera.py

      • Camera Matrix calculation in set_matching_fisheye_polynomial_properties method in Camera.py

      • Camera class to work with torch backend

      • Contact Sensor can now measure force correctly when the rigid body is not its direct parent

  • omni.isaac.surface_gripper

    • Changed

      • Location on the Menu reverted back to from Create->Isaac->End Effector

      • Location on the Menu changed from Create->Isaac->End Effector to Create->Isaac->Robot.

  • omni.isaac.synthetic_recorder

    • Changed

      • removed overwrite/increment/timestamp options from recorder, it is now handled by the backend which is not exposed

    • Fixed

      • fixed bug if a non valid json file is provided to the custom writer

  • omni.isaac.synthetic_utils

    • Changed

      • disabling unit tests that are failing due to deprecated interfaces

  • omni.isaac.universal_robots

    • Added

      • Random piece orientation on drop

    • Changed

      • Minor tweaks in bin filling position so pieces don’t hit robot when falling

  • omni.isaac.urdf

    • Changed

      • Added deprecation alert. This extension has been deprecated, please use omni.importer.urdf instead.

  • omni.isaac.utils

    • Changed

      • Removed Factory Franka

    • Fixed

      • April tag menu

      • Loading Robotiq hand into a path that doesn’t start with a number

  • omni.isaac.wheeled_robots

    • Changed

      • OgnAckermannSteering node receives inputs in SI units.

      • OgnAckermannSteering node now accepts speed and acceleration as desired forward motion inputs.

      • OgnAckermannSteering node uses front axel steering angle as input rather than curvature

      • Moved wheel base pose controller from motion generation extension

    • Fixed

      • _wheeled_dof_indices vs _wheel_dof_indices typo

  • omni.kit.property.isaac

    • Changed

      • Prim Custom Data field can support arrays now

  • omni.replicator.isaac

    • Added

      • DataVisualizationWriter writing annotattions as overlays on top of image data

      • DOPE and YCBWriter will write to disk only if there is valid data (target(s) is not fully occluded in view)

    • Fixed

      • Change initialization of s3 BackendDispatch for DOPE writer

      • Added overwrite=True by default to DOPE and YCV Writer backends

      • DataVisualizationWriter parameters if None and writer metadata export

2023.1.0-hotfix.1

Highlights

  • General

    • Fixes for security vulnerabilities: CVE-2023-38545, CVE-2023-5590

Extensions

  • omni.isaac.examples

    • Fixed

      • Changed end offector offset for Franka Stacking Controller in robo party example to [0, 0, 0] instead of [0, 0, -0.015]

  • omni.isaac.ros2_bridge

    • Fixed

      • Added fix for foxy backend to match humble backend

  • omni.isaac.ros_bridge

    • Fixed

      • Logging levels for roscore helper

  • omni.isaac.ui

    • Fixed

      • Error when user setup function creates a new stage

      • Error when using load button due to physics context initialization issue

  • omni.kit.loop-isaac

    • Changed

      • Update to latest loop runner code from kit-sdk and set default settings

2023.1.0

Highlights

  • General

  • ROS

    • Update packages to python 3.10

    • ROS2 Bridge now enabled by default

    • ROS2 bridge can dynamically load based on the workspace sourced

    • Developers can source their Humble or Foxy workspaces before running Omniverse Isaac Sim

    • Developers can leverage their ROS 2 installation to write and compile C++ OmniGraph Nodes

    • Sample workflow for using ROS 2 custom messages with Python:rclpy

    • Navigation with RTX lidar

    • ROS2 Single and Multi robot navigation examples using the new Nova Carter robot

    • ROS2 Humble support for Windows

    • Reduced GPU-CPU memory copies to improve performance

  • New robots

    • Evobot from Fraunhofer

    • Manipulators: Fanuc CRX-10iA, Festo Cobot, KUKA KR 210 L150, Techman TM12

    • Mobile base: Nova Carter

  • Sensors

    • New Sensors

    • RGBD: Realsense, Orbbec, Hawk, Sensing

    • RTX-Lidar: Zvision, Ouster, Hesai, Sick, Velodyne, SlamTec

    • RTX-lidar in windows

    • Camera class

  • Manipulation

    • Mimic joint support in URDF importer and Lula kinematics, inverse kinematics, and trajectory generator

    • Robot Assembler for composing robots and end effectors

  • Replicator

    • Randomization in simulation (manipulator use case)

    • Randomization in simulation (mobile base use case)

    • Offline data generation with config files (YAML/JSON) support

    • Writer and annotator augmentations

    • Isaac Sim / USD API based randomizations

  • Warehouse Builder

    • Use new modular warehouse assets

  • Gym

    • Tensorized soft body API and RL example

    • Additional RL examples for Factory tasks

    • New RL examples with Warp

    • Extension workflow for RL training and inferencing

    • Support for multi-node RL training

  • Cortex

    • Extension for palletizing demo

    • Visualization of logical states

  • Live Streaming

    • WebSocket streaming client is deprecated

  • Container

    • Added telemetry support for container

    • Updated base container to Ubuntu 22.04

  • Documentation

    • Isaac Sim Documentation Audits. Audit & reg-org Isaac Sim docs to make it useful for first time users.

    • Updated Motion Generation tutorials to use standalone extensions instead of standalone scripts

Extensions

  • omni.exporter.urdf

    • Added new omni.exporter.urdf extension.

  • omni.isaac.app.selector

    • Changed

      • Added a note that “Headless WebSocket” app variant is now deprecated and will be removed in a future release.

      • Set ROS bridge field to blank so users can pick if they want to start with ROS1/ROS2

      • Source bash when starting sim so env vars are properly set

  • omni.isaac.app.setup

    • Added

      • Added “ReplicatorYAML” menu item.

    • Removed

      • Removed F1 and F3 hotkeys for opening help documents.

    • Changed

      • Updated contents of “Help” menu.

      • Added deprecation label for the “Replicator -> Composer” menu item.

      • Removed redundant settings that were already set in .kit file.

    • Fixed

      • Fixed an issue that prevented fullscreen and “Hide UI” modes from working.

  • omni.isaac.articulation_inspector

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

      • Replaced use of get_joint_efforts() with get_measured_joint_efforts() since the former had been deprecated and is now removed.

  • omni.isaac.asset_browser

    • Changed

      • Updated asset paths to those for the 2023.1.0 release.

      • Added “Materials” folder to the asset browser.

  • omni.isaac.camera_inspector

    • Added new omni.isaac.camera_inspector extension.

  • omni.isaac.cloner

    • Added

      • Exposed API for retrieving clone transorms from GridCloner

      • Add unregister when physics replication is disabled

      • Added option to specify mode of cloning (inherit vs. copy)

    • Changed

      • When positions and orientations are None, the cloner keeps the Xform translation and orientation instead of using identity

      • Makes the method replicate_physics public to allow users to have control over it

  • omni.isaac.conveyor

    • Changed

      • added standard out fail pattern for the expected no prim found edge case for the ogn test

      • Changed conveyor prim node input type from bundle to target

      • Update to kit 105.1, build system update, omni.usd.utils -> omni.usd, usdPhysics -> pxr/usd/usdPhysics

  • omni.isaac.core

    • Added

      • Add missing GPU collision stack size API in physics context

      • Add function create_viewport_for_camera() to viewports.py

      • get_local_pose and get_world_pose in xforms utils which will go through fabric if the prim exists there, otherwise it will read it from USD

      • Added SdfShapeView class for handling shapes signed-distance function

      • Added a new API for reading detailed contact data

      • Added support for Warp backend for rigid classes

      • Added core wrappers for physx and physics.tensors deformable body APIs

      • Added new APIs for joint force sensors and dof effort sensors

      • Added OBB functions compute_obb and compute_obb_corners to utils.bounds

      • Added OBB tests

      • euler_to_rot_matrix returns the pre multiplicative matrix and not the post multiplicative one as before and in numpy format intead of Gf.Rotation.

      • added extrinsic argument to torch rotation utils: compute_rot, quat_from_euler_xyz, get_euler_xyz, euler_angles_to_quats

      • added methods to torch rotation utils: quat_to_rot_matrices, matrices_to_euler_angles

      • added extrinsic argument to numpy rotation utils: quats_to_euler_angles, euler_angles_to_quats

      • added extrinsic argument to rotation utils: euler_angles_to_quat, quat_to_euler_angles, matrix_to_euler_angles, euler_to_rot_matrix

    • Changed

      • Changed get_world_pose fabric util to check for the attribute before getting it to avoid warnings

      • Added warnings to OgnIsaacReadFilePath

      • Updated view port unit test to accept identical fx and fy

      • XFormPrimView get_local_poses and get_world_poses uses the new methods available in xforms utils to query the poses from Fabric and USD alike

      • timeline is stopped if initialize simulation context is called

      • Split World reset_async into scene construction and simulation start.

      • Add function get_transform_with_normalized_rotation to utils.transformation.py

      • Function returns transformation matrix after removing scale factor

      • Update asset paths to 2023.1.0

    • Fixed

      • Correctly set GPU pipeline when it is missing from SimConfig

      • Propagate physX to Fabric when stepping physX and kit seperatly

      • Articulation Root mismatch with the default state in ArticulationView

      • Fixed a bug in a rigid_prim_view unit test

      • Fixed gpu device parsing.

      • Added gpu flushing as a physics callback to handle the extension workflow and the standalone one alike.

      • Removed the destructor calls from SimulationContext and World for possible bugs concerning them being Singeltons.

      • GeometryPrimView.is_collision_enabled to read values set through USD and not the class

      • GeometryPrimView.get_physics_visual_materials typo to use physics material rather than visual material

      • None in numpy arrays in current numpy version 1.25.2 gets converted to nan, propagated this change to ArticulationController.apply_action

      • Fixed the __new__ method in the SimulationContext class to work for inherited class.

      • Updated utils.viewports.set_camera_view to check both x and y of the position and target

      • Add default values for World transform attributes when fetching fabric in _get_world_pose_transform_w_scale method

      • Vertical Aperture used from reading the horizonal aperture usd property and multiplying it by resolution ratio to conform to the square pixels asumption in place. (setting and getting intrinsics in viewports utils)

      • Crash when initializing world if is_playing was true

      • Fixed memory leak in ArticulationView, RigidPrimView and SimulationContext stemming from tensor api views

      • Fixed minor typo in articulation view

      • Fixed the order of parsing of the stage in the physics context warm start operation

      • set_camera_view now works when the camera is directly above or directly below the target (x and y positions are equal)

      • Issues related to Kit 105.1 update

      • UsdShaderConnecatbleAPI explicit for OmniGlass and PreviewSurface constructors

      • Renamed flatcache to fabric (enable_flatcache -> enable fabric in PhysicsContext) and sim_params dict key use_flatcache -> use_fabric

      • Extension omni.physx.flatcache renamed to omni.physx.fabric

      • Schema attributes moved from CLoth API to Particle API in ClothPrimView class

      • SimulationContext sets TimeCodesPerSecond attribute and the timeline’s target framrate to the rendering frequency to account for the decoupling of stage updates and app updates.

      • set_prop_val move from omni.usd.utils to omni.usd

  • omni.isaac.core_archive

    • Removed

      • boto3, s3transfer to omni.pip.compute

      • scipy, pyyaml to omni.pip.compute

      • botocore, urllib3, charset-normalizer as they are already in omni.kit.pip_archive

    • Changed

      • Removed unused omni.kit.pipapi dependency

  • omni.isaac.core_nodes

    • Added

      • Added tracking for the number of physics step

      • IsaacReadTimes node

      • get_sim_time_at_time

      • get_sim_time_monotonic_at_time

      • get_system_time_at_time

      • IsaacReadTimesAOV node template

      • IsaacReadTimes node template

      • Support for custom distortion type/values on a camera to read camera info node

    • Removed

      • unused writer and node template attachment systems

      • IsaacReadSystemTime node

      • swhFrameTime input/output from IsaacConvertRGBAToRGB node

    • Changed

      • Read file node will return False if file path does not exist or is invalid

      • Add enabled flag to create render product node

      • Added a default noop node to SDG pipeline helper nodes so that the graph is not deleted on stop

      • added stdout fail pattern for the expected no prim found edge case for the ogn test

      • Changed omnigraph prim from bundle to target for OgnIsaacComputeOdometry, OgnIsaacArticulationController, OgnIsaacCreateRenderProduct, OgnIsaacSetCameraOnRenderProduct

      • Use Replicator Annotator class for nodes that can provide data

      • Point Cloud node returns width and height of data

      • RGBA and Depth to PCL nodes use raw ptrs instead of arrays to improve perf

      • Update to kit 105.1, build system update

      • IsaacArticulationController targetPrim now optional

      • getSimulationTimeAtSwhFrame now getSimulationTimeAtTime with rational time

      • getSimulationTimeMonotonicAtSwhFrame now getSimulationTimeMonotonicAtTime with rational time

      • getSystemTimeAtSwhFrame now getSystemTimeAtTime with rational time

      • [SENSOR NAME]IsaacSimulationGate nodes to [RENDERVAR]IsaacSimulationGate to match synthetic data standard

      • deprecated get_sim_time_at_swh_frame

      • deprecated get_sim_time_monotonic_at_swh_frame

      • deprecated get_system_time_at_swh_frame

    • Fixed

      • ReadTimes node not passing execution state properly

      • Fixed camera info is empty bug in test_camera

      • Import error in OgnIsaacGetViewportRenderProduct

      • Added time code settings for test_physics_num_steps

      • Vertical Aperture used from reading the horizonal aperture usd property and multiplying it by resolution ratio to conform to the square pixels asumption in place. (DepthToPointCloud and IsaacReadCameraInfo nodes)

  • omni.isaac.cortex

    • Added

      • __str__ methods for Df and Dfb classes

    • Fixed

      • omni.isaac.kit dependency

      • Conversion from Rotation matrix Quaternion uses direct method

  • omni.isaac.cortex.sample_behaviors

    • Added new omni.isaac.cortex.sample_behaviors extension.

  • omni.isaac.cortex_sync

    • Fixed

      • Prevents messages to be sent when their content is null

  • omni.isaac.debug_draw

    • Added

      • doTransform to DebugDrawPointCloud node, set to false it ignores the input transform

      • xPrim Axis Visualzier node

      • xPrim Radius Visualizer node

    • Changed

      • added stdout fail pattern for the expected no prim found edge case for the ogn test

      • Added testMode and removed depthTest (it did nothing) from DebugDrawPointCloud node.

      • Changed prim input type from bundle to target for xPrim Axis and Radius visualizer

      • rename width to size for point cloud debug node to prevent auto connection when using in replicator pipelines

      • pass width vector by reference.

      • Simplified DebugDrawPointCloud internals.

      • DebugDrawPointCloud Node updated to work with dataPtr/bufferSize inputs.

      • DebugDrawPointCloud Node updated to auto connect with synthetic data/replicator nodes.

  • omni.isaac.dynamic_control

    • Changed

      • Update to kit 105.1, update build system

      • set_time_codes_per_second in set_physics_frequency

    • Fixed

      • Fixed joints on the root of an articulation are treated as a special type of internal articulation to support fixed base.

      • Getting the type for the first fixed joint on the root link of an articulation will return none now

      • Use USD apis to interact with the first fixed joint on the root of an articulation.

  • omni.isaac.examples

    • Added

      • Cortex Samples

    • Removed

      • Moved Cortex Behaviors to omni.isaac.cortex.sample_behaviors

    • Fixed

      • Collision groups and num_bolts for nut and bolt extension

      • Changed end offector offset in pick and place examples using Franka to [0, 0, 0] instead of [0, 0, -0.015]

      • Fixed quadruped example error after reset or stop

      • Incorrect scaling factor in Omnigraph Keyboard example

      • Physics/lighting error caused by 100x scale in cube size and camera position

      • Error in nut+bolt example due to USD schema changes

      • Missing cortex dependency

      • Fix for Nut and Bolt Demo Windows Bug

  • omni.isaac.examples_nodes

    • Changed

      • Changed robot prim type from bundle to target

      • Update to kit 105.1

      • make targetPrim on IsaacPickPlaceController node optional

  • omni.isaac.extension_templates

    • Added

      • Added limitations to special characters that are considered acceptible in an extension title

      • Added XYPlot to “UI Component Library Template”

      • Added “Status Frame” to Extension Template Generator to give feedback to the user to guide their usage. Feedback includes verification that their templates were generated properly.

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

    • Fixed

      • Fixed bug in Template generator on Windows where user could specify a file path ending in “/”.

      • Fixed bug in Loaded Scenario Template where XFormPrim no longer accepts an Sdf.Path

      • Fixed bug where Configuration Tooling Template could cause a crash in Kit 105.1

      • The crash was caused by attempting to initialize Articulation on all stage events. The fix is to subscribe specifically to the ASSETS_LOADED stage event.

      • Subscriptions to STOP/PLAY timeline events in the Configuration Tooling Template have been removed, as they didn’t acheive anything when running Kit 105.1

      • Extension templates now use the extension name to generate python module paths to prevent clashing python modules. Previously, all modules were named “scripts” and you could not enable multiple extension templates at once.

  • omni.isaac.gain_tuner

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.gym

    • Added

      • Base RLTask and domain randomization utils are now part of omni.isaac.gym

      • Include web browser clients for livestream

      • Add automated inferencing tests

      • Add missing SAC and Factory tests

      • Add multi-GPU tests

    • Changed

      • Enable fabric in app file since updateToUsd is set to False

      • Add device ID to cuda device

      • Move domain randomization util back to OIGE

      • Keep lightweight interface for RLTask

      • Use async calls for pre and post physics steps in MT workflow

      • Allow passing app file as argument to VecEnvBase

      • Update app files for gym

      • Redesign MT env for extension workflow

      • Update interface from gym to gymnasium

      • Added explicit omni.kit.pipapi dependency

      • Skip replicator wait for complete on shutdown to avoid hang

    • Fixed

      • Fix Windows tests pip install error

      • Close app if sim is terminated

      • Handle ctrl+c events on shutdown

  • omni.isaac.kit

    • Added

      • Faulthandler enabled to print callstack on crash

    • Changed

      • Add flag to SimulationApp close to skip replicator wait for complete

    • Fixed

      • Missing comma in sync load options

      • various linter issues

      • app framework not working in docker/root environments

      • simulation app startup warning

      • Fix potential error on Kit shutdown when Replicator capture on play is enabled

  • omni.isaac.lula

    • Changed

      • Upgraded Lula from release 0.8.2 to release 0.9.1. This new version includes a major overhaul of inverse kinematics (IK), improving performance and robustness via many performance optimizations and the addition of a BFGS solver used to refine the solution produced by the existing cyclic coordinate descent (CCD) solver. The names of certain parameters in the CyclicCoordDescentIkConfig struct have changed, breaking backward compatibility. This update also includes the fix for a bug that could affect CCD convergence and the addition of “mimic joint” support throughout.

      • Added “[Lula]” prefix to all Lula log messages.

    • Fixed

      • Added a workaround for a DLL loading issue under Windows that manifested when using the new “FastImporter” in Omniverse Kit 105.

  • omni.isaac.lula_test_widget

    • Changed

      • Updated Controllers due to changes to motion generation ArticulationTrajectory

  • omni.isaac.merge_mesh

    • Changed

      • Update to kit 105.1, omni.usd.utils -> omni.usd

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.mjcf
    • Changed
      • Deprecating omni.isaac.mjcf, extension renamed to omni.importer.mjcf

  • omni.isaac.ml_archive

    • Changed

      • Added version to omni.pip.torch dependency

      • Removed unused omni.kit.pipapi dependency

      • no longer depend on omni.pip.torch

  • omni.isaac.motion_generation

    • Added

      • Add Fanuc CRX10IAL rmpflow configs with corresponding test case

      • Add Kuka KR210 rmpflow configs with corresponding test case

      • Update function in test cases that ensures deterministic behavior corresponding to moving to Kit 1.05

      • Add RMPflow config for Techman TM12 robot

      • Added support for timestamped Lula c-space trajectory generation with corresponding test cases.

    • Changed

      • Breaking Change: Updated ArticulationTrajectory, PathPlannerVisualizer, and ArticulationKinematics to use ArticulationSubset.make_articulation_action() This will result in ArticulationActions being returned that have fewer dimensions because they are not padded with Nones

      • Made stronger changes to IK interface to expose every property available in the Lula IK solver.

      • Made minimal internal changes to IK interface for compatibility with Lula 0.9.0.

      • Increase threshold on RRT test

      • Update RRT tests to use LulaTrajectoryGenerator to ensure that the robot Articulation more closely follows the ideal RRT path.

    • Fixed

      • Updated path of Kuka KR210 robot in test case to match update to Nucleus Server

      • lula.TaskSpaceTrajectoryGenerator.compute_task_space_trajectory_from_path_spec() was not able to handle lula composite path specs

      • Fixed robot loading in Trajectory Generator test cases to use add_reference_to_stage() instead of open_stage()

      • Fixed a bug in LulaKinematicsSolver that had resulted in set_descent_termination_delta() having no effect.

      • Add light to stages in all motion generation test cases because Kit 105.1 no longer has a default stage light

      • add_block function in motion_policy tests no longer waiting a frame before teleporting the block. The single frame of collision was causing the robot in the test cases to explode.

      • Broken test for RRT fixed by creating a more conservative robot description for Franka with spheres inflated by 5%.

  • omni.isaac.occupancy_map

    • Added

      • Checkbox to use USD triangle geometry instead of physx approx for occupancy map generation. Useful for generating occupancy maps for PhysX vs RTX lidar.

    • Changed

      • Update to kit 105.1, update build system

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.ocs2

    • Changed

      • Updated ocs2 prebundle for kit 105.1

  • omni.isaac.onshape

    • Changed

      • Use pip_prebundle instead of runtime installation of pip packages

      • Added explicit omni.kit.pipapi dependency

      • Update to kit 105.1, omni.usd.utils -> omni.usd

    • Fixed

      • Support for documents with Variable Studio

      • Automatically download when part configuration changes

      • Referenced assets would fail to import correctly if the user didn’t have direct access to the original document.

      • Joints limits defined by configuration or variable studio would fail to import correctly.

  • omni.isaac.partition

    • Changed

      • Update to kit 105.1, update build system

  • omni.isaac.physics_inspector

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.physics_utilities

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.proximity_sensor

    • Changed

      • Update to kit 105.1, omni.usd.utils -> omni.usd

  • omni.isaac.quadruped

    • Changed

      • Eliminated dependency on “bezier” python package. Behavior is unchanged.

    • Fixed

      • Fixed robot articulation bug after stop or reset

  • omni.isaac.range_sensor

    • Added

      • get_prim_data, returns the prim path for each lidar hit, use this to access semantic data on a prim

      • Lidar now tracks time at which each beam was traced. (Bug 4143606)

      • OgnIsaacReadLidarBeams provides beam times as output. (Bug 4143606)

    • Removed

      • get_semantic_data returns an empty array

    • Changed

      • Renamed Create > Isaac > Sensor > Lidar to PhysX Lidar

      • Output of IsaacReadLidarPointCloud changed from pointCloudData to data

      • Added standard out fail pattern for the expected no prim found edge case for the ogn test

      • Changed lidar prim types from bundle to target

      • Update to kit 105.1

      • usd 22.11 schema inheritance

      • pxr::RangeSensorSchemaUltrasonicArray renamed pxr::RangeSensorUltrasonicArray

      • pxr::RangeSensorSchemaUltrasonicFiringGroup renamed pxr::RangeSensorUltrasonicFiringGroup

      • pxr::RangeSensorSchemaUltrasonicEmitter renamed pxr::RangeSensorUltrasonicEmitter

      • pxr::RangeSensorSchemaLidar renamed pxr::RangeSensorLidar

      • pxr::RangeSensorSchemaGeneric renamed pxr::RangeSensorGeneric

      • pxr::RangeSensorSchemaRangeSensor renamed pxr::RangeSensorRangeSensor

    • Fixed

      • Fixed blackness in sensor examples

      • app update event subscribers in examples are created even when not using example

  • omni.isaac.robot_assembler

    • Added new omni.isaac.robot_assembler extension.

  • omni.isaac.robot_benchmark

    • Changed

      • Update Golden Values in tests due to Kit version 105.1

    • Fixed

      • Import order issue due to code formatting

  • omni.isaac.robot_description_editor

    • Changed

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

  • omni.isaac.ros2_bridge

    • Added

      • Added enable flag for the lidar and camera helper

      • Improved description for the frame ID for the camera and lidar helper

      • Add menu item for Isaac ROS VSLAM tutorial

      • Tests for JointState Publisher

    • Changed

      • Made several warnings into print and log statements

      • Load internal ROS2 libs when ROS2 is not sourced

      • Print warning telling user how to source ROS2 to use internal libs with rclpy

      • load system rclpy, fallback onto internal rclpy if its not found

      • Re-written to use rclc APIs

      • User must source their local ROS2 workspace in the terminal before starting isaac sim

      • Foxy and humble are supported

      • The ROS_DISTRO env variable is used to determine what ROS backend to use

      • The separate Humble bridge extension has been removed

      • added stdout fail pattern for the expected no prim found edge case for the ogn test

      • Changed test_camera test to expect identical fx and fy as vertical aperture is computed from horizontal aperture.

      • Changed omnigraph targetPrim types from bundle to target

      • Image and PCL publishers to use ptrs instead of arrays when possible to reduce memory copies

      • Update to kit 105.1

      • rename synthetic data writer templates to match rendervar names

      • Disable extension if rclpy cannot load

      • Set ROS2 Context node to read ROS_DOMAIN_ID from env vars by default

    • Fixed

      • Windows message for setting PATH

      • rclpy not working in script editor

      • Transform tree node can accept multiple target prims as input

      • missing ros2 libs when running using internal libs

      • windows startup issues

      • rclpy not working on windows

      • clock subscriber not properly getting time

      • error when shutting down extension

      • properly handle case where ROS2 bridge carb plugin did not startup correctly

      • Add default values for World transform attributes when fetching fabric in computeWorldXformNoCache function used in processAllFrames

      • Pixel are square in 105.1 Vertical aperture is not used, and based off of horizontal

      • Joint efforts not being applied in joint state subscriber

      • Added fix for foxy backend to match humble backend

      • CameraInfo publisher now includes identity Rectification matrix

      • Joint State Subscriber supports input state messages with only one mode of drive specified

      • camera noise example errors

      • Moveit Tutorial had incorrect OG input name

      • Bug with ROS2 windows loading internal libs

      • JointState Publisher sign correction when a joint’s parents are in reversed order

  • omni.isaac.ros_bridge

    • Added

      • Removed context field from OgnROS1RtxLidarHelper OG node

      • Added enable flag for the lidar and camera helper

      • Improved description for the frame ID for the camera and lidar helper

      • Sync and async versions of checking for rosmaster

      • Tests for JointState Publisher

    • Changed

      • Added standard out fail pattern for the expected no prim found edge cases for the ogn test

      • Changed test_camera test to expect identical fx and fy as vertical aperture is computed from horizontal aperture.

      • Changed targetPrim datatype from bundle to target in omnigraph

      • Image and pcl nodes support gpu/cpu ptr data

      • Image and PCL publishers to use ptrs instead of arrays when possible to reduce memory copies

      • renamed wait_for_rosmaster to wait_for_rosmaster_async

      • Update to kit 105.1

      • add lib locations to PYTHONPATH

      • rename synthetic data writer templates to match rendervar names

    • Fixed

      • Transform tree node can accept multiple target prims as input

      • CUDA error in PCL publisher

      • Semantic publisher not correctly publishing bbox, semantics, instances

      • Add default values for World transform attributes when fetching fabric in computeWorldXformNoCache function used in processAllFrames

      • Pixel are square in 105.1 Vertical aperture is not used, and based off of horizontal

      • Bug in Joint Subscriber when using effort commands

      • CameraInfo publisher now includes identity Rectification matrix

      • Moveit Tutorial had incorrect OG input name

      • JointState Publisher sign correction when a joint’s parents are in reversed order

  • omni.isaac.scene_blox

    • Added

      • omni.isaac.scene_blox.grid_utils.config - Maintains global RNG.

    • Changed

      • Updates all modules to use newly-added global RNG, enabling replicability by setting seed.

  • omni.isaac.sensor

    • Added

      • numEchos, numChannels, and numTicks output to IsaacReadRTXLidarData

      • depthRange output to IsaacReadRTXLidarData

      • IsaacPrintRTXLidarInfo outputs largest velocity length

      • IsaacCreateRTXLidarScanBuffer node outputs all possible lidar data based on output flags on node.

      • Support, samples for OpenCV calibration models

      • Sensing GMSL2 RGBD sensors

      • transformPoints setting on IsaacCreateRTXLidarScanBuffer to enable correct world transformed points.

      • Velodyne and ZVISION RTX lidar config files.

      • Sick_TiM781 lidar config file.

      • testMode to IsaacPrintRTXRadarInfo

      • Writers for radar point cloud node

      • Effort sensor standalone example

      • Sensor buffer size test for effort sensor and IMU

      • Added menu items for more RTX Lidar sensor configs

      • Changed isaac sensor node prim from bundle to target type

      • Add function to camera.py to scrap all Camera objects in the scene

      • Added IsaacCreateRTXLidarScanBuffer Node

      • Changed contact sensor and IMU node prim from bundle to target type

      • docstrings to Camera class for functions adding annotators

      • Added support for ros and usd camera axes in get_world_pose, get_local_pose, set_world_pose, set_local_pose.

      • Added Effort Sensor

      • supported_annotators property

      • Add unit tests for Camera class to test get_point_cloud(), get_depth(), get_rgb()

      • Add following functions to Camera class

      • get_point_cloud()

      • get_depth()

      • get_rgb()

      • added get_sensor_reading function

      • Added RGBD sensors to Create > Isaac > Sensors menu

      • RTX Sensors to Windows

      • WriterIsaacReadRTXLidarData Synthetic Data Writer

      • RtxSensorCpuIsaacReadRTXLidarData Synthetic Data Template

      • Added filter width attributes to the imu sensor for adjusting noise

      • Added unit test for imu sensor filter, and repeated imu sensor readings

      • get_render_product_path to camera class

      • An existing render product path can be specified for the camera helper class

      • bounding_box_3d annotator to camera class

      • Test Mode for PrintRTXLidarInfo node.

      • synthetic data templates for Noop, RtxSensorCpuIsaacPrintRTXLidarInfo, and TestIsaacPrintRTXLidarInfo

      • TemplateRtxLidarDebugDrawPointCloud Synthetic Data template that mirrors the RtxLidarDebugDrawPointCloud writer.

    • Removed

      • RtxRadarGetPrimLocalToWorldTransform

      • IsaacRenderVarToCpuPointer, use omni.syntheticdata.SdRenderVarPtr instead.

    • Changed

      • changed IU names for CreateRTXLidarScanBuffer outputs to be more user friendly.

      • set default RXT sensor space to be the same as isaac-sim so rotations in IsaacSensorCreateRtxLidar make sense

      • updated data acquisition callback for Camera objects to be on the next frame event

      • Used frameTime annotator instead of the dispather node inputs for better accuracy in the data acquisition callback

      • Moved initializing render products to the initialize method in Camera to reduce overhead and decoupling the usage of pose utils and render product related methods

      • RGBD menu updated to include manufacturer sub-menu

      • Updated usd paths for Sensing assets

      • Changed base prim type for sensors from Camera to Xform (real camera sensor should be inside of the default prim)

      • IsaacComputeRTXLidarFlatScan now works with single emitter lidar configs like RPLIDAR_S2E

      • Added Kannala Brandt and Rational Polynomial tests for the camera properties test

      • Updated USD path for NVIDIA Hawk RGBD sensor

      • The IMU now gets the transform from world directly.

      • IMU can have intermediate parents that are non rigid body.

      • IMU can measure or ignore gravitational acceleration via read_gravity flag

      • The layout of the add sensors menu.

      • on CreateRTXLidarScanBuffer returnsPerScan output to numReturnsPerScan

      • Added standard out fail pattern for the expected no prim found edge case for the ogn test

      • Cleaned up IsaacComputeRTXLidarPointCloud, no intended functional changes.

      • RtxSensorCpuIsaacComputeRTXRadarPointCloud template to Annotator

      • Radar Point Cloud creator now gets transform from render_product

      • changed PrintRTX templates to Writers

      • Effort sensor omnigraph node update sensor params

      • Unified input param names for get_sensor_reading across sensors

      • RTX point cloud node returns width and height of buffer

      • Convert RTX templates to annotators

      • store and destroy internaly created renderproduct

      • get_current_frame() now accepts optional argument to return deepcopy of data

      • RTX Nodes updated to work with dataPtr/cudaDeviceIndex/bufferSize inputs and outputs.

      • RTX Nodes updated to auto connect with synthetic data/replicator nodes.

      • RTX Node and DebugDrawPointCloud templates and writers updated to auto connect with synthetic data/replicator nodes.

      • Changed sensor reading behavior that prohibit interpolation when the sensor frequency is higher than physics frequency

      • Uses data interpolated at previous sensor measurement period when it’s lower than physics frequency for the IMU sensor and nearest physics step data for the contact sensor

      • Deprecated get_sensor_readings, get_sensor_sim_reading, get_sensor_num_reading for IMU Sensor and Contact Sensor

      • Changed orientation measurement to be the orientation of the IMU sensor rather than the parent prim

      • Changed contact sensor logic to process sensor measurement every step instead of on call

      • Updated ant sensor samples to use the new API

      • Updated python wrapper and removed callbacks.

      • Location of default and temp lidar config files set to ${app}/../data/sensors/lidar/

      • IsaacPrintRTXLidarInfo works with changed rtx lidar data

      • IsaacReadRTXLidarData outputs match changed rtx lidar data

      • If /app/runLoops/main/rateLimitFrequency is not set Frequency goes to -1, and all frames are captured

      • IsaacPrintRTXLidarInfo node now prints prim paths and return data for first named prim hits.

      • Update to kit 105.1

      • RTX Lidar/Radar Nodes cleanup

      • Location of default and temp lidar config files set to ${app}/../data/lidar/

      • Removed pxr::Simulation Gate from Rtx[Lidar|Radar]DebugDrawPointCloud writers

      • renamed pxr::IsaacSensorSchemaIsaacBaseSensor to pxr::IsaacSensorIsaacBaseSensor

      • renamed pxr::IsaacSensorSchemaIsaacContactSensor to pxr::IsaacSensorIsaacContactSensor

      • renamed pxr::IsaacSensorSchemaIsaacImuSensor to pxr::IsaacSensorIsaacImuSensor

      • get_all_camera_objects() now ensures that camera names are unique

      • Updated assets to use carter v2.4

      • Changed sensor type member names to adhere to naming conventions, inContact to in_contact

    • Fixed

      • Fixed WriterReadRTXLidarData Synthetic Data writer so it sets the render_product_path correctly.

      • Fixed elevation output for ComputeRTXLidarPointCloud node.

      • Fixed bug with ReadRTXLidarData node output when using keepOnlyPositiveDistance.

      • Add the allowedToken metadata for the cameraProjectionType attribute in cameras if it wasn’t set already.

      • Fixed bug with horizontal resolution divison

      • Fixed contact sensor sample

      • ComputeRTXLidarFlatScan now uses lidar config for more accurate output

      • IsaacComputeRTXLidarFlatScan range projected to 0 elevation

      • IMU and contact sensor read omnigraph nodes can now support parents from multiple levels up.

      • Scale issues with Orbbec RGBD sensors

      • RtxLidarDebugDrawPointCloudBuffer writer to use correct default transform

      • RTX Lidar Menu setting wrong config parameter on sensor prim

      • Added force threshold unit test for the contact sensor, now contact forces smaller than the min threshold will be treated as no contact

      • CreateRTXLidarScanBuffer works when input data wraps around the output buffer

      • CreateRTXLidarScanBuffer works on Solid State Lidar

      • Improved unit test stability

      • keepOnlyPositiveDistance now works on CreateRTXLidarScanBuffer node

      • Sensor buffer bug for effort sensor and IMU

      • Vertical Aperture used from reading the horizonal aperture usd property and multiplying it by resolution ratio to conform to the square pixels asumption in place. (Camera class)

      • RTX lidar class not returning data

      • Fixed divisible by zero error in IMU linear interpolation

      • Removed reading pairs from the IMU sensor to use the buffer directly

      • Error when removing an annotator that had not been added yet

      • Fixed index out of bound error for the read IMU and contact sensor nodes

      • Imu frequency to downtime calculation has been fixed

      • Bug causing the data frame to stop updating in the camera class over extended periods of time

      • Missing connection for IsaacComputeRTXLidarPointCloud node

      • removed extra frame transformation in the LidarRtx wrapper

      • changed physX lidar tests and samples to use Carter V1

      • Realsense D455 menu

  • omni.isaac.shapenet

    • Changed

      • Deprecation warning to UI and shapenet_convert

      • Added explicit omni.kit.pipapi dependency

      • Modified extension to use ScrollingWindow wrapper since ui.Window in Kit 105.1 no longer supports scrolling by default.

    • Fixed

      • Remove explicit certifi dependency and use omni.kit.pip_archive

  • omni.isaac.surface_gripper

    • Changed

      • Updated ogn node to prevent issue where it would only call for close on first attempt.

      • Automatically move gripper origin out of collision body, with a warning to tell how much to push it forward

      • Updated ogn node prims types from bundle to ogn

  • omni.isaac.synthetic_recorder

    • Added

      • custom names for render products

      • render products are destroyed after each recording

      • select all and toggle all buttons for writer annotator parameters

    • Changed

      • increased render product max resolution to 16kx8k

    • Fixed

      • omni.pip.cloud dependency is needed for replicator.core deps

      • load_config checks for empty json files

  • omni.isaac.synthetic_utils

    • Changed

      • deprecated in favor of omni.replicator.core, omni.syntheticdata and omni.isaac.sensor

  • omni.isaac.tests

    • Added

      • Joint effort test, with pure usd joints and articulation joints

      • omni.anim.people extension startup test

      • Added Test Cases that cause segfaults in the current build of Isaac Sim

      • Added Test Case to check if Sim will freeze when opening a USD stage 100 times

    • Removed

      • Moved multi-cam utility snippet to standalone_examples/omni.isaac.snippets/

    • Changed

      • Changed test accel, test spin, and test circle thresholds for the carter v1, v2 and jetbot

      • Changed unit tests as the prim types of omnigraph nodes have been changed from bundle to target

      • Update to kit 105.1, omni.usd.utils renamed omni.usd

      • Refactor and fix broken tests

      • Combined and cleaned up tests

      • use set_target_prims from core nodes

    • Fixed

      • Fixed drive_goal_carter_v2 tests to use the correct timecode setting

      • Added timecode to stage for test_stage_up_axis and test_stage_units

      • Fixed articulation_drives_opposite.usd file errors

      • Fixed broken mobile robot tests

  • omni.isaac.ui

    • Added

      • Added ScrollingWindow UI wrapper now that Kit 105.1 windows do not automatically have a scrollbar.

      • Added test cases for UI widget wrappers

      • Added test cases for UI Core Connectors

      • Added UIElementWrapper XYPlot with significantly more useful plotting utility than the base omni.ui.Plot

    • Changed

      • Update build_header() function to use constant colors

    • Fixed

      • Fixed possible errors in UI Plotting Tool where x_min is set arbitrarily close to x_max beyond what was a hard-coded constant.

      • Fixed possible errors in UI Plotting Tool that can be caused by spamming updates to violate x_max > x_min on X axis. Fixed error when floats are overflowed, which allowed x_min to equal x_max for high numbers

      • Added extra frame of waiting when using LoadButton and ResetButton after core.World.reset(). The extra frame resolves possible differences in rendered object position and queried position.

      • Fixed unused on event function for string builder

      • Fixed small bugs found in UI widget wrappers

      • Enforce argument types in setter functions for UI Widget Wrappers by casting [int,float,bool] args to their required type explicitly. This handles undesirable behavior that arises when numpy types such as np.float are passed instead of primitive types. For example, the FloatField displays the value 0.0:np.float as 1.0.

  • omni.isaac.unit_converter

    • Fixed

      • UsdLux api change from Light to LightApi

  • omni.isaac.urdf

    • Changed

      • Deprecating omni.isaac.urdf, renaming it to omni.importer.urdf

  • omni.isaac.utils

    • Added

      • getCameraPrimFromRenderProduct function

      • Added new robots to Create -> Isaac -> Robots menu

      • Carter V2.4 asset path, removed Carter V2 and V2.3

      • Renamed Carter V2.4 Nova Carter

    • Changed

      • updated Create > Isaac > Robots menu

      • Update to kit 105.1, omni.usd.utils renamed omni.usd

    • Fixed

      • Updated path of Kuka KR210 robot to match update to Nucleus Server

      • Updated name of Kuka KR210 robot in Create menu.

      • Broken asset paths

  • omni.isaac.version

    • Fixed

      • Scan for test modules instead of importing them

      • Docs and docstrings

      • Fixed closing of parsed file for reading the version

  • omni.isaac.wheeled_robots

    • Added

      • Ackermann Steering OmniGraph node

    • Changed

      • wheeled robot class can now accept a relative path from the default prim to the robot prim when the robot is not the default prim

    • Fixed

      • Changed robot prim types from bundle to target in Omnigraph

      • Kit 105.1 update

      • use omni.usd instead of omni.usd.utils for get_world_transform_matrix

      • Differential controller will not ignore 0s as max speed inputs.

      • Differential controller now resets on simulation Stop

  • omni.kit.loop-isaac

    • Changed

      • Update to kit 105.1, pybind11 header locations

    • Fixed

      • Crash on exit due to threading race condition

  • omni.kit.property.isaac

    • Changed

      • Update to kit 105.1

      • python 3.11 super().__init__ added

  • omni.pip.cloud

    • Added new omni.pip.cloud extension.

  • omni.pip.compute

    • Added new omni.pip.compute extension.

  • omni.replicator.isaac

    • Added

      • register_pose_annotator() to DOPEWriter and YCBVideoWriter

      • setup_writer() to DOPEWriter and YCBVideoWriter

      • Functions were originally in standalone_examples/replicator/pose_generation/pose_generation.py

      • Moved into dope_writer.py and ycb_video_writer.py

    • Changed

      • Improved pytorch writer performance

      • Update to kit 105.1

      • removed swhFrameNumber from Pose and Dope nodes

    • Fixed

      • Fix error when AOVs return data on different devices

      • test_pytorch_writer adding the num_frames to run_until_complete_async due to possible off-by-one frame issue

      • Fixes for physics APIs

      • Fixes for updated replicator API

  • omni.usd.schema.isaac

    • Changed

      • Direct inheritance for IsA schema IsaacContactSensor, IsaacImuSensor, Lidar, UltrasonicArray, Generic

      • Updated for USD 22.11 and Kit 105.1.

      • Using omni-isaacsim-schema as dependency