Unverified Commit e7f68669 authored by Pascal Roth's avatar Pascal Roth Committed by GitHub

Fixes tutorials on sensors (#301)

# Description

This MR reorganizes the sensor tutorials. Hence, there is only one sensor
tutorial introducing spawning sensors to an `InteractiveScene` and
some minimal tutorials for other sensors. The USD camera tutorial is
converted into a how-to save camera image.

Note: the how-to has to be fixed in a separate PR as we have to see what
is the best way to save images efficiently, the Replicator Writer might
have been updated in the meantime.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [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

---------
Co-authored-by: 's avatarMayank Mittal <mittalma@leggedrobotics.com>
parent b0c01d49
......@@ -12,8 +12,8 @@ use Orbit. If you are new to Orbit, we recommend you start with the tutorials.
.. toctree::
:maxdepth: 1
:numbered:
write_articulation_cfg
save_camera_output
draw_markers
wrap_rl_env
.. _how-to-save-images-and-3d-reprojection:
Saving rendered images and 3D re-projection
===========================================
.. currentmodule:: omni.isaac.orbit
This how-to demonstrates an efficient saving of rendered images and the projection of depth images into 3D Space.
It is accompanied with the ``run_usd_camera.py`` script in the ``orbit/source/standalone/tutorials/04_sensors``
directory. For an introduction to sensors, please check the :ref:`tutorial-add-sensors-on-robot` tutorials.
Saving the Images
-----------------
To save the images, we use the basic write class from Omniverse Replicator. This class allows us to save the
images in a numpy format. For more information on the basic writer, please check the
`documentation <https://docs.omniverse.nvidia.com/extensions/latest/ext_replicator/writer_examples.html>`_.
.. literalinclude:: ../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 135-137
:linenos:
:lineno-start: 135
While stepping the simulator, the images can be saved to the defined folder.
Since the BasicWriter only supports saving data using NumPy format, we first need to convert the PyTorch sensors
to NumPy arrays before packing them in a dictionary.
.. literalinclude:: ../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 172-193
:linenos:
:lineno-start: 172
Projection into 3D Space
------------------------
In addition, we provide utilities to project the depth image into 3D Space.
The re-projection operations are done using torch which allows us to use the GPU for faster computation.
The resulting point cloud is visualized using the :mod:`omni.isaac.debug_draw` extension from Isaac Sim.
.. literalinclude:: ../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 197-229
:linenos:
:lineno-start: 197
Setting up a Simple Simulation
==============================
These tutorials show you how to launch the simulation with different settings and spawn objects in the
simulated scene. They cover the following APIs: :class:`~omni.isaac.orbit.app.AppLauncher`,
:class:`~omni.isaac.orbit.sim.SimulationContext`, and :class:`~omni.isaac.orbit.sim.spawners`.
.. toctree::
:maxdepth: 1
:titlesonly:
......
Interacting with Assets
=======================
Having spawned objects in the scene, these tutorials show you how to create physics handles for these
objects and interact with them. These revolve around the :class:`~omni.isaac.orbit.assets.AssetBase`
class and its derivatives such as :class:`~omni.isaac.orbit.assets.RigidObject` and
:class:`~omni.isaac.orbit.assets.Articulation`.
.. toctree::
:maxdepth: 1
:titlesonly:
run_articulation
run_rigid_object
run_articulation
Creating a Scene
================
With the basic concepts of the framework covered, the tutorials move to a more intuitive scene
interface that uses the :class:`~omni.isaac.orbit.scene.InteractiveScene` class. This class
provides a higher level abstraction for creating scenes easily.
.. toctree::
:maxdepth: 1
:titlesonly:
......
Designing an Environment
========================
The following tutorials introduce the concept of environments: :class:`~omni.isaac.orbit.envs.BaseEnv`
and its derivative :class:`~omni.isaac.orbit.envs.RLTaskEnv`. These environments bring-in together
different aspects of the framework to create a simulation environment for agent interaction.
.. toctree::
:maxdepth: 1
:titlesonly:
......
Adding Sensors on a Robot
.. _tutorial-add-sensors-on-robot:
Adding sensors on a robot
=========================
This tutorial demonstrates how to simulate various sensors onboard the quadruped robot ANYmal-C (ANYbotics) using the ORBIT framework. The included sensors are:
.. currentmodule:: omni.isaac.orbit
While the asset classes allow us to create and simulate the physical embodiment of the robot,
sensors help in obtaining information about the environment. They typically update at a lower
frequency than the simulation and are useful for obtaining different proprioceptive and
exteroceptive information. For example, a camera sensor can be used to obtain the visual
information of the environment, and a contact sensor can be used to obtain the contact
information of the robot with the environment.
- USD-Camera
- Height Scanner
- Contact Sensor
In this tutorial, we will see how to add different sensors to a robot. We will use the
ANYmal-C robot for this tutorial. The ANYmal-C robot is a quadrupedal robot with 12 degrees
of freedom. It has 4 legs, each with 3 degrees of freedom. The robot has the following
sensors:
- A camera sensor on the head of the robot which provides RGB-D images
- A height scanner sensor that provides terrain height information
- Contact sensors on the feet of the robot that provide contact information
We continue this tutorial from the previous tutorial on :ref:`tutorial-interactive-scene`,
where we learned about the :class:`scene.InteractiveScene` class.
Please review their how-to guides before proceeding with this guide.
The Code
~~~~~~~~
......@@ -20,84 +38,173 @@ The tutorial corresponds to the ``add_sensors_on_robot.py`` script in the
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:emphasize-lines: 72-90, 116-123, 125-139, 150-151
:emphasize-lines: 73-96, 145-154, 172-173
:linenos:
The Code Explained
~~~~~~~~~~~~~~~~~~
The script designs a scene with a ground plane, lights, and two instances of the ANYmal-C robot.
This guide will not explain the individual sensors; please refer to their corresponding how-to guides for more details (see :ref:`Height-Scanner How-to-Guide <how_to_ray_caster_label>` and :ref:`Camera How-to-Guide <how_to_camera_label>`).
Furthermore, how to spawn such an articulated robot in the scene is explained in the :ref:`Articulation How-to-Guide <how_to_articulation_label>`.
Similar to the previous tutorials, where we added assets to the scene, the sensors are also added
to the scene using the scene configuration. All sensors inherit from the :class:`sensors.SensorBase` class
and are configured through their respective config classes. Each sensor instance can define its own
update period, which is the frequency at which the sensor is updated. The update period is specified
in seconds through the :attr:`sensors.SensorBaseCfg.update_period` attribute.
Depending on the specified path and the sensor type, the sensors are attached to the prims in the scene.
They may have an associated prim that is created in the scene or they may be attached to an existing prim.
For instance, the camera sensor has a corresponding prim that is created in the scene, whereas for the
contact sensor, the activating the contact reporting is a property on a rigid body prim.
In the following, we introduce the different sensors we use in this tutorial and how they are configured.
For more description about them, please check the :mod:`sensors` module.
In the following, we will detail the ``add_sensor`` function, which is responsible for adding the sensors on the robot.
The ``run_simulator`` function updates the sensors and provides some information on them.
Camera sensor
-------------
Adding the sensors
------------------
A camera is defined using the :class:`sensors.CameraCfg`. It is based on the USD Camera sensor and
the different data types are captured using Omniverse Replicator API. Since it has a corresponding prim
in the scene, the prims are created in the scene at the specified prim path.
For each sensor, the corresponding config class has to be created, and the corresponding parameters have to be set.
To add the sensors to the robot, the prim paths must be set as a child prim of the robot.
In this case, the sensor will move with the robot. The offsets have to be provided w.r.t. the parent frame on the robot.
The resulting configurations and initialization calls are shown below.
The configuration of the camera sensor includes the following parameters:
Camera sensor:
* :attr:`~sensors.CameraCfg.spawn`: The type of USD camera to create. This can be either
:class:`~sim.spawners.sensors.PinholeCameraCfg` or :class:`~sim.spawners.sensors.FisheyeCameraCfg`.
* :attr:`~sensors.CameraCfg.offset`: The offset of the camera sensor from the parent prim.
* :attr:`~sensors.CameraCfg.data_types`: The data types to capture. This can be ``rgb``,
``distance_to_image_plane``, ``normals``, or other types supported by the USD Camera sensor.
To attach an RGB-D camera sensor to the head of the robot, we specify an offset relative to the base
frame of the robot. The offset is specified as a translation and rotation relative to the base frame,
and the :attr:`~sensors.CameraCfg.OffsetCfg.convention` in which the offset is specified.
In the following, we show the configuration of the camera sensor used in this tutorial. We set the
update period to 0s to update the sensor at simulation frequency. The prim path is set to
``{ENV_REGEX_NS}/Robot/base/front_cam`` where the ``{ENV_REGEX_NS}`` is the namespace of the environment,
``"Robot"`` is the name of the robot, ``"base"`` is the name of the prim to which the camera is attached,
and ``"front_cam"`` is the name of the prim associated with the camera sensor.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:lines: 88-102
:lines: 74-84
:linenos:
:lineno-start: 88
:lineno-start: 74
Height scanner sensor
---------------------
The height-scanner is implemented as a virtual sensor using the NVIDIA Warp ray-casting kernels.
Through the :class:`sensors.RayCasterCfg`, we can specify the pattern of rays to cast and the
meshes against which to cast the rays. Since they are virtual sensors, there is no corresponding
prim created in the scene for them. Instead they are attached to a prim in the scene, which is
used to specify the location of the sensor.
Height scanner sensor:
For this tutorial, the ray-cast based height scanner is attached to the base frame of the robot.
The pattern of rays is specified using the :attr:`~sensors.RayCasterCfg.pattern` attribute. For
a uniform grid pattern, we specify the pattern using :class:`~sensors.patterns.GridPatternCfg`.
Since we only care about the height information, we do not need to consider the roll and pitch
of the robot. Hence, we set the :attr:`~sensors.RayCasterCfg.attach_yaw_only` to true.
For the height-scanner, you can visualize the points where the rays hit the mesh. This is done
by setting the :attr:`~sensors.SensorBaseCfg.debug_vis` attribute to true.
The entire configuration of the height-scanner is as follows:
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:lines: 103-114
:lines: 85-93
:linenos:
:lineno-start: 103
:lineno-start: 85
Contact sensor
--------------
Contact sensors wrap around the PhysX contact reporting API to obtain the contact information of the robot
with the environment. Since it relies of PhysX, the contact sensor expects the contact reporting API
to be enabled on the rigid bodies of the robot. This can be done by setting the
:attr:`~sim.spawners.RigidObjectSpawnerCfg.activate_contact_sensors` to true in the asset configuration.
Contact sensor:
Through the :class:`sensors.ContactSensorCfg`, it is possible to specify the prims for which we want to
obtain the contact information. Additional flags can be set to obtain more information about
the contact, such as the contact air time, contact forces between filtered prims, etc.
In this tutorial, we attach the contact sensor to the feet of the robot. The feet of the robot are
named ``"LF_FOOT"``, ``"RF_FOOT"``, ``"LH_FOOT"``, and ``"RF_FOOT"``. We pass a Regex expression
``".*_FOOT"`` to simplify the prim path specification. This Regex expression matches all prims that
end with ``"_FOOT"``.
We set the update period to 0 to update the sensor at the same frequency as the simulation. Additionally,
for contact sensors, we can specify the history length of the contact information to store. For this
tutorial, we set the history length to 6, which means that the contact information for the last 6
simulation steps is stored.
The entire configuration of the contact sensor is as follows:
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:lines: 115-120
:lines: 94-96
:linenos:
:lineno-start: 115
:lineno-start: 94
Running the simulation loop
---------------------------
Please note that the buffers, physics handles for the camera and robot, and other aspects are initialized when the simulation is played. Thus, we must call ``sim.reset()``.
Similar to when using assets, the buffers and physics handles for the sensors are initialized only
when the simulation is played, i.e., it is important to call ``sim.reset()`` after creating the scene.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:lines: 181-182
:lines: 172-173
:linenos:
:lineno-start: 181
:lineno-start: 173
Besides that, the simulation loop is similar to the previous tutorials. The sensors are updated as part
of the scene update and they internally handle the updating of their buffers based on their update
periods.
Running the simulation loop
---------------------------
For every simulation step, the sensors are updated and we print some information.
The data from the sensors can be accessed through their ``data`` attribute. As an example, we show how
to access the data for the different sensors created in this tutorial:
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
:language: python
:lines: 150-168
:lines: 148-158
:linenos:
:lineno-start: 150
:lineno-start: 148
The Code Execution
~~~~~~~~~~~~~~~~~~
Now that we have gone through the code let's run the script and see the result:
Now that we have gone through the code, let's run the script and see the result:
.. code-block:: bash
./orbit.sh -p source/standalone/tutorials/04_sensors/add_sensors_on_robot.py
./orbit.sh -p source/standalone/tutorials/04_sensors/add_sensors_on_robot.py --num_envs 2
This command should open a stage with a ground plane, lights, and two quadrupedal robots.
To stop the simulation, you can either close the window, press the ``STOP`` button in the UI, or press ``Ctrl+C`` in the terminal.
Around the robots, you should see red spheres that indicate the points where the rays hit the mesh.
Additionally, you can switch the viewport to the camera view to see the RGB image captured by the
camera sensor. Please check `here <https://youtu.be/htPbcKkNMPs?feature=shared>`_ for more information
on how to switch the viewport to the camera view.
To stop the simulation, you can either close the window, or press ``Ctrl+C`` in the terminal.
While in this tutorial, we went over creating and using different sensors, there are many more sensors
available in the :mod:`sensors` module. We include minimal examples of using these sensors in the
``source/standalone/tutorials/04_sensors`` directory. For completion, these scripts can be run using the
following commands:
.. code-block:: bash
# Frame Transformer
./orbit.sh -p source/standalone/tutorials/04_sensors/run_frame_transformer.py
# Ray Caster
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster.py
# Ray Caster Camera
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
In this guide, we saw how to add sensors to a robot and how to update them in the simulation loop.
# USD Camera
./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py
Integrating Sensors
===================
The following tutorial shows you how to integrate sensors into the simulation environment. The
tutorials introduce the :class:`~omni.isaac.orbit.sensors.SensorBase` class and its derivatives
such as :class:`~omni.isaac.orbit.sensors.Camera` and :class:`~omni.isaac.orbit.sensors.RayCaster`.
.. toctree::
:maxdepth: 1
:titlesonly:
add_sensors_on_robot
run_frame_transformer
run_ray_caster
run_ray_caster_camera
run_usd_camera
.. _how_to_frame_transformer_label:
Using the Frame Transformer
===========================
This tutorial demonstrates using the :class:`FrameTransformer` sensor in the ORBIT framework.
The :class:`FrameTransformer` sensor is used to report the transformation of one or more frames (target frames) with respect to another frame (source frame)
The Code
~~~~~~~~
The tutorial corresponds to the ``run_frame_transformer.py`` script in the
``orbit/source/standalone/tutorials/04_sensors`` directory.
.. dropdown:: Code for run_frame_transformer.py
:icon: code
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_frame_transformer.py
:language: python
:emphasize-lines: 72-90, 116-123, 125-139, 150-151
:linenos:
The Code Explained
~~~~~~~~~~~~~~~~~~
As usual, we design a minimal scene for this example. In addition to the GroundPlane and a Distant Light, we spawn a quadrupedal robot.
Spawning such an articulated robot in the scene is explained in the :ref:`Articulation How-to-Guide <_how_to_articulation_label>`.
In the following, we will detail the ``add_sensor`` function, responsible for adding the ray caster sensor to the scene.
The ``run_simulator`` function visualizes the different frames given the computed transforms from the sensor and passes the default actions to the robot.
Adding the frame transformer sensor
-----------------------------------
As usual, the frame transformer is defined over its config class, :class:`FrameTransformerCfg`.
We need to specify the source frame (`prim_path`) and the target frames for the Frame Transformer sensor.
The source frame is the frame with respect to which the translations are reported.
We can specify a list of frames for the target frames and include regex patterns to match multiple frames.
In some cases, the target frame is not an individual prim; its relation to a "parent" prim can be defined over an offset.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_frame_transformer.py
:language: python
:lines: 72-90
:linenos:
:lineno-start: 72
Please note that the buffers, physics handles for the robot, and other aspects are initialized when the simulation is played. Thus, we must call ``sim.reset()``.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_frame_transformer.py
:language: python
:lines: 150-151
:linenos:
:lineno-start: 150
Running the simulation loop
---------------------------
After each step call, we must update the frame transformer sensor to get the latest transforms.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_frame_transformer.py
:language: python
:lines: 116-123
:linenos:
:lineno-start: 116
To visualize the transforms, we visualize a different frame in a regular interval based on the transform reported by the sensor.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_frame_transformer.py
:language: python
:lines: 125-139
:linenos:
:lineno-start: 125
The Code Execution
~~~~~~~~~~~~~~~~~~
Now that we have gone through the code let's run the script and see the result:
.. code-block:: bash
./orbit.sh -p source/standalone/tutorials/04_sensors/run_frame_transformer.py
This should open a stage with a ground plane, lights, and a quadrupedal robot. Consistently, one frame should be visualized.
To stop the simulation, you can either close the window, press the ``STOP`` button in the UI, or press ``Ctrl+C`` in the terminal.
In this guide, we saw how to use a frame transformer sensor. In the following how-to guides, other sensors will be introduced, and how to place sensors on the robot will be explained.
.. _how_to_ray_caster_label:
Using the Ray-Caster
====================
This tutorial demonstrates using the :class:`RayCaster` sensor from the Orbit framework.
Here, we present its usability as a height-scanner, but it can also be used as LiDAR or for any other purpose achieved by ray-casting.
The Code
~~~~~~~~
The tutorial corresponds to the ``run_ray_caster.py`` script in the
``orbit/source/standalone/tutorials/04_sensors`` directory.
.. dropdown:: Code for run_ray_caster.py
:icon: code
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster.py
:language: python
:emphasize-lines: 84-94, 100-117, 137-138, 118-123
:linenos:
The Code Explained
~~~~~~~~~~~~~~~~~~
As usual, we design a minimal scene for this example. In addition to the GroundPlane and a Distant Light, for this how-to guide, we add some spheres to the scene that are wrapped as a RigidObject to access their position, orientation, and velocity.
In the following, we will detail the ``add_sensor`` function, responsible for adding the raycaster sensor to the scene.
Adding the ray-caster sensor
----------------------------
As usual, the ray-caster is defined over its config class, :class:`RayCasterCfg`.
Unlike the Camera sensor, the ray-caster operates as a virtual sensor and does not require instantiation within the scene. Instead, it is solely attached to a prim, employed to specify its location, along with a potential offset. This attachment allows the ray-caster to cast a predetermined pattern of rays against a mesh.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster.py
:language: python
:lines: 84-94
:linenos:
:lineno-start: 84
Please note that the buffers, physics handles for the RigidObject, and other aspects are initialized when the simulation is played. Thus, we must call ``sim.reset()``.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster.py
:language: python
:lines: 137-138
:linenos:
:lineno-start: 137
.. attention::
Currently, ray-casting is only supported against a single mesh. We are working on extending this functionality to multiple meshes.
Running the simulation loop
---------------------------
In this tutorial, we step the simulation and reset the position of the spheres to initial random positions. For a detailed explanation of the simulation loop, please refer to the :ref:`RigidObject How-to-Guide <_how_to_rigid_objects_label>`.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster.py
:language: python
:lines: 100-117
:linenos:
:lineno-start: 100
For the ray-caster sensor, we execute the ray-casting operation. Here, we also time this operation to give an impression of how much time such operations require.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster.py
:language: python
:lines: 118-123
:linenos:
:lineno-start: 118
The Code Execution
~~~~~~~~~~~~~~~~~~
Now that we have gone through the code let's run the script and see the result:
.. code-block:: bash
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster.py
This command should open a stage with a ground plane, lights, and some spheres first falling and then rolling on rough terrain with a raycaster pattern next to them.
To stop the simulation, you can either close the window, press the ``STOP`` button in the UI, or press ``Ctrl+C`` in the terminal.
In this guide, we saw how to use a ray-caster sensor. In the following how-to guide, we will see how to use the ray-caster sensor as a faster camera when only geometric information is required.
Using the Ray-Caster Camera
===========================
This tutorial demonstrates using the :class:`RayCasterCamera` sensor as a depth camera from the Orbit framework.
We already saw how to use the USD camera sensor (see :ref:`Camera How-to-Guide <how_to_camera_label>`) and the ray-caster sensor when used as a height scanner (see :ref:`Height Scanner How-to-Guide <how_to_ray_caster_label>`).
As the current implementation of the ray-caster is faster and more memory efficient than the USD camera sensor, it is a good alternative when only geometric information is required.
The interfaces for both cameras are identical, including the data buffers they use. However, the initialization configuration differs slightly as no spawn configuration is required for the ray-caster camera.
The Code
~~~~~~~~
The tutorial corresponds to the ``run_ray_caster_camera.py`` script in the
``orbit/source/standalone/tutorials/04_sensors`` directory.
.. dropdown:: Code for run_ray_caster_camera.py
:icon: code
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:emphasize-lines: 68-88,94-106,111-145,156-157
:linenos:
The Code Explained
~~~~~~~~~~~~~~~~~~
We designed a minimal scene for this example, composed of a rough terrain and a distant light.
In the following, we will detail the ``add_sensor`` function, which is responsible for adding the raycaster sensor to the scene, and the ``run_simulator`` function, which steps the simulator and saves the rendered images.
Adding the ray-caster camera sensor
-----------------------------------
As usual, the ray-caster camera is defined over its config class, :class:`RayCasterCameraCfg`.
Like the ray-casting-based height scanner and unlike the USD camera, the ray-caster operates as a virtual sensor and does not require a spawn within the scene. Instead, it is solely attached to a prim, employed to specify its location, along with a potential offset.
For the ray-caster camera, we specify the pinhole camera pattern. The pattern config includes the camera intrinsics and the image dimension, which will define the direction of the rays.
Other parameters are defined in the general config, as they are independent of the pattern. These include data types, offset, or the mesh to be ray-casted against.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:lines: 68-88
:linenos:
:lineno-start: 68
Please note that the buffers and other aspects are initialized when the simulation is played. Thus, we must call ``sim.reset()``.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:lines: 156-157
:linenos:
:lineno-start: 156
.. attention::
Currently, ray-casting is only supported against a single mesh. We are working on extending this functionality to multiple meshes.
Running the simulation loop
---------------------------
In this tutorial, we step the simulation and efficiently render and save the camera images. To save the images, we use the Replicator BasicWriter (more information `here <www.docs.omniverse.nvidia.com/isaacsim/latest/replicator_tutorials/tutorial_replicator_recorder.html?highlight=basic%20writer#writer-parameters>`_).
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:lines: 94-96
:linenos:
:lineno-start: 94
The camera's position and orientation can be set within the config by defining the offset relative to the parent frame. Alternatively, we can set the position and orientation of the camera directly in the scene. In this example, we provide two options for the latter: either by providing the camera center and a target point (:meth:`RayCasterCamera:set_world_poses_from_view`) or by providing the camera center and a rotation quaternion (:meth:`RayCasterCamera:set_world_poses_from_view`). To allow for maximum flexibility, the provided quaternions can be provided in three conventions:
* ``"opengl"`` - forward axis: -Z - up axis +Y - OpenGL (Usd.Camera) convention
* ``"ros"`` - forward axis: +Z - up axis -Y - ROS convention
* ``"world"`` - forward axis: +X - up axis +Z - World Frame convention
This behavior is the same as for the USD camera.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:lines: 98-106
:linenos:
:lineno-start: 98
While stepping the simulator, we update the camera and write the images to the defined folder. Therefore, we first convert them to numpy arrays before packing them in a dictionary, which the BasicWriter can handle.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
:language: python
:lines: 111-145
:linenos:
:lineno-start: 111
The Code Execution
~~~~~~~~~~~~~~~~~~
Now that we have gone through the code let's run the script and see the result:
.. code-block:: bash
./orbit.sh -p source/standalone/tutorials/04_sensors/run_ray_caster_camera.py
This call should open a stage with a ground plane, lights, and a visualization of the points where the rays hit the mesh.
To stop the simulation, you can either close the window, press the ``STOP`` button in the UI, or press ``Ctrl+C`` in the terminal.
In this guide, we saw how to use a ray-caster camera sensor. Moving forward, we will see how sensors can be used further and how to combine and place them on a robot.
.. _how_to_camera_label:
Using the Camera Sensor
=======================
This tutorial demonstrates using the :class:`Camera` from the Orbit framework. The camera sensor is created and interfaced through the Omniverse Replicator API.
The Code
~~~~~~~~
The tutorial corresponds to the ``run_usd_camera.py`` script in the
``orbit/source/standalone/tutorials/04_sensors`` directory.
.. dropdown:: Code for run_usd_camera.py
:icon: code
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:emphasize-lines: 102-112,113-114,121-123,125-133,135-139,140-141,155-179,181-215
:linenos:
The Code Explained
~~~~~~~~~~~~~~~~~~
As usual, we design a minimal scene for this example. In addition to the GroundPlane and a Distant Light, we add some simple shapes to the scene for this how-to guide.
In the following, we will detail the ``add_sensor`` function, responsible for adding the camera to the scene, and the ``run_simulator`` function, which steps the simulator and saves the rendered images.
Adding the camera sensor
------------------------
As Orbit is a config-driven framework, the camera is defined over its config class, :class:`CameraCfg`. Whereas parameters that do not depend on the used camera type are direct arguments of this class, all camera type-related arguments are defined in the spawn config. With the camera type, we refer to either PinholeCamera or FisheyeCamera. The type-independent parameters are, e.g., the data types to capture (e.g., "rgb," "distance_to_image_plane," "normals," "motion_vectors," "semantic_segmentation"), the width and height of the image and its offset. The spawn configurations defined parameters such as the aperture or the focus distance. These are given together with all other spawn-related configs under :class:`PinholeCameraCfg` and :class:`FisheyeCameraCfg`.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 102-112
:linenos:
:lineno-start: 102
While in previous how-to guides, we had to manually call the function to spawn the object into the scene, sensors already include this functionality when initialized. Consequently, we only have to pass the ``camera_cfg`` to the :class:`Camera` class.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 113-114
:linenos:
:lineno-start: 113
Please note that the Replicator Render Products, camera buffers and other aspects are initialized when the simulation is played. Thus, we must call ``sim.play()`` before rendering camera images.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 140-141
:linenos:
:lineno-start: 140
Running the simulation loop
---------------------------
In this tutorial, we step the simulation and efficiently render and save the camera images. To save the images, we use the Replicator BasicWriter (more information `here <www.docs.omniverse.nvidia.com/isaacsim/latest/replicator_tutorials/tutorial_replicator_recorder.html?highlight=basic%20writer#writer-parameters>`_).
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 121-123
:linenos:
:lineno-start: 121
The camera's position and orientation can be set within the config by defining the offset relative to the parent frame. Alternatively, we can set the position and orientation of the camera directly in the scene. In this example, we provide two options for the latter: either by providing the camera center and a target point (:meth:`Camera:set_world_poses_from_view`) or by providing the camera center and a rotation quaternion (:meth:`Camera:set_world_poses_from_view`). To allow for maximum flexibility, the provided quaternions can be provided in three conventions:
* ``"opengl"`` - forward axis: -Z - up axis +Y - OpenGL (Usd.Camera) convention
* ``"ros"`` - forward axis: +Z - up axis -Y - ROS convention
* ``"world"`` - forward axis: +X - up axis +Z - World Frame convention
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 125-133
:linenos:
:lineno-start: 125
While stepping the simulator, we write the images to the defined folder. Therefore, we first convert them to numpy arrays before packing them in a dictionary, which the BasicWriter can handle.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 155-179
:linenos:
:lineno-start: 155
In addition, we provide the functionality to project the depth image into 3D space. This reprojection is done by using the camera intrinsics and the depth image. The resulting point cloud is visualized using the ``_debug_draw`` extension of Isaac Sim.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 181-215
:linenos:
:lineno-start: 99
.. attention::
For all replicator buffers to be filled with the latest data, we may need to render the simulation multiple times.
.. literalinclude:: ../../../../source/standalone/tutorials/04_sensors/run_usd_camera.py
:language: python
:lines: 135-139
:linenos:
:lineno-start: 135
The Code Execution
~~~~~~~~~~~~~~~~~~
Now that we have gone through the code, let's run the script and see the result:
.. code-block:: bash
./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py
This should open a stage with a ground plane, lights, and some slowly falling down objects.
To stop the simulation, you can either close the window, press the ``STOP`` button in the UI, or press ``Ctrl+C`` in the terminal.
This guide showed how to spawn a camera into the scene and save data. The following guides present other sensors and the possibility of putting them on a robot.
Using Motion Generators
=======================
While the robots in the simulation environment can be controlled at the joint-level, the following
tutorials show you how to use motion generators to control the robots at the task-level.
.. toctree::
:maxdepth: 1
:titlesonly:
......
......@@ -2,79 +2,23 @@ Tutorials
=========
Welcome to the Orbit tutorials! These tutorials provide a step-by-step guide to help you understand
and use various features of the framework. We recommend that you go through the tutorials in the
order they are listed here.
All the tutorials are written as Python scripts. You can find the source code for each tutorial in
the ``source/standalone/tutorials`` directory of the Orbit repository.
and use various features of the framework. All the tutorials are written as Python scripts. You can
find the source code for each tutorial in the ``source/standalone/tutorials`` directory of the Orbit
repository.
.. note::
We would love to extend the tutorials to cover more topics and use cases, so please let us know if
you have any suggestions.
.. toctree::
:maxdepth: 1
:titlesonly:
00_sim/index
These tutorials show you how to launch the simulation with different settings and spawn objects in the
simulated scene. They cover the following APIs: :class:`~omni.isaac.orbit.app.AppLauncher`,
:class:`~omni.isaac.orbit.sim.SimulationContext`, and :class:`~omni.isaac.orbit.sim.spawners`.
We recommend that you go through the tutorials in the order they are listed here.
.. toctree::
:maxdepth: 1
:titlesonly:
:maxdepth: 2
00_sim/index
01_assets/index
Having spawned objects in the scene, these tutorials show you how to create physics handles for these
objects and interact with them. These revolve around the :class:`~omni.isaac.orbit.assets.AssetBase`
class and its derivatives such as :class:`~omni.isaac.orbit.assets.RigidObject` and
:class:`~omni.isaac.orbit.assets.Articulation`.
.. toctree::
:maxdepth: 1
:titlesonly:
02_scene/index
With the basic concepts of the framework covered, the tutorials move to a more intuitive scene
interface that uses the :class:`~omni.isaac.orbit.scene.InteractiveScene` class. This class
provides a higher level abstraction for creating scenes easily.
.. toctree::
:maxdepth: 1
:titlesonly:
03_envs/index
The following tutorials introduce the concept of environments: :class:`~omni.isaac.orbit.envs.BaseEnv`
and its derivative :class:`~omni.isaac.orbit.envs.RLTaskEnv`. These environments bring-in together
different aspects of the framework to create a simulation environment for agent interaction.
.. toctree::
:maxdepth: 1
:titlesonly:
04_sensors/index
The following tutorials show you how to integrate sensors into the simulation environment. These
tutorials introduce the :class:`~omni.isaac.orbit.sensors.SensorBase` class and its derivatives
such as :class:`~omni.isaac.orbit.sensors.FrameTransformer` and :class:`~omni.isaac.orbit.sensors.RayCaster`.
.. toctree::
:maxdepth: 1
:titlesonly:
05_controllers/index
While the robots in the simulation environment can be controlled at the joint-level, the following
tutorials show you how to use motion generators to control the robots at the task-level.
......@@ -30,6 +30,7 @@ from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="Tutorial on adding sensors on a robot.")
parser.add_argument("--num_envs", type=int, default=2, help="Number of environments to spawn.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
......@@ -47,45 +48,32 @@ import traceback
import carb
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import Articulation
from omni.isaac.orbit.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.orbit.assets.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.sensors import (
Camera,
CameraCfg,
ContactSensor,
ContactSensorCfg,
RayCaster,
RayCasterCfg,
patterns,
)
def design_scene() -> tuple[Articulation, tuple[tuple[Camera], tuple[RayCaster], tuple[ContactSensor]]]:
"""Design the scene."""
# Populate scene
# -- Ground-plane
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# -- Lights
cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# -- robot
anymal_c_cfg = ANYMAL_C_CFG
anymal_c_cfg.spawn.func("/World/Anymal_c/Robot_1", anymal_c_cfg.spawn, translation=(1.5, -1.5, 0.65))
anymal_c_cfg.spawn.func("/World/Anymal_c/Robot_2", anymal_c_cfg.spawn, translation=(1.5, -0.5, 0.65))
anymal_c = Articulation(anymal_c_cfg.replace(prim_path="/World/Anymal_c/Robot.*"))
# adds different sensors
sensors = add_sensors()
return anymal_c, sensors
def add_sensors() -> tuple[tuple[Camera], tuple[RayCaster], tuple[ContactSensor]]:
"""Adds sensors to the robot."""
# -- usd camera
camera_cfg = CameraCfg(
update_period=0,
from omni.isaac.orbit.scene import InteractiveScene, InteractiveSceneCfg
from omni.isaac.orbit.sensors import CameraCfg, ContactSensorCfg, RayCasterCfg, patterns
from omni.isaac.orbit.utils import configclass
@configclass
class SensorsSceneCfg(InteractiveSceneCfg):
"""Design the scene with sensors on the robot."""
# ground plane
ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
# lights
dome_light = AssetBaseCfg(
prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
)
# robot
robot: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# sensors
camera = CameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base/front_cam",
update_period=0.0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane"],
......@@ -94,42 +82,26 @@ def add_sensors() -> tuple[tuple[Camera], tuple[RayCaster], tuple[ContactSensor]
),
offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
)
cameras = (
camera_cfg.class_type(camera_cfg.replace(prim_path="/World/Anymal_c/Robot_1/base/front_cam")),
camera_cfg.class_type(camera_cfg.replace(prim_path="/World/Anymal_c/Robot_2/base/front_cam")),
)
# -- height scanner
height_scanner_cfg = RayCasterCfg(
height_scanner = RayCasterCfg(
prim_path="{ENV_REGEX_NS}/Robot/base",
update_period=0.02,
offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)),
attach_yaw_only=True,
pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]),
debug_vis=True,
mesh_prim_paths=["/World/defaultGroundPlane"],
)
height_scanner = (
height_scanner_cfg.class_type(height_scanner_cfg.replace(prim_path="/World/Anymal_c/Robot_1/base")),
height_scanner_cfg.class_type(height_scanner_cfg.replace(prim_path="/World/Anymal_c/Robot_2/base")),
)
# -- contact sensors
contact_forces_cfg = ContactSensorCfg(history_length=3, track_pose=True)
contact_forces = (
contact_forces_cfg.class_type(contact_forces_cfg.replace(prim_path="/World/Anymal_c/Robot_1/.*")),
contact_forces_cfg.class_type(contact_forces_cfg.replace(prim_path="/World/Anymal_c/Robot_2/.*")),
contact_forces = ContactSensorCfg(
prim_path="{ENV_REGEX_NS}/Robot/.*_FOOT", update_period=0.0, history_length=6, debug_vis=True
)
return cameras, height_scanner, contact_forces
def run_simulator(
sim: sim_utils.SimulationContext,
robot: Articulation,
sensors: tuple[tuple[Camera], tuple[RayCaster], tuple[ContactSensor]],
scene: InteractiveScene,
):
"""Run the simulator."""
# unpack sensors
cameras, height_scanner, contact_forces = sensors
# Define simulation stepping
sim_dt = sim.get_physics_dt()
sim_time = 0.0
......@@ -137,51 +109,72 @@ def run_simulator(
# Simulate physics
while simulation_app.is_running():
# apply default actions to the quadrupedal robots
robot.set_joint_position_target(robot.data.default_joint_pos.clone())
robot.write_data_to_sim()
# Reset
if count % 500 == 0:
# reset counter
count = 0
# reset the scene entities
# root state
# we offset the root state by the origin since the states are written in simulation world frame
# if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
root_state = scene["robot"].data.default_root_state.clone()
root_state[:, :3] += scene.env_origins
scene["robot"].write_root_state_to_sim(root_state)
# set joint positions with some noise
joint_pos, joint_vel = (
scene["robot"].data.default_joint_pos.clone(),
scene["robot"].data.default_joint_vel.clone(),
)
joint_pos += torch.rand_like(joint_pos) * 0.1
scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
# clear internal buffers
scene.reset()
print("[INFO]: Resetting robot state...")
# Apply default actions to the robot
# -- generate actions/commands
targets = scene["robot"].data.default_joint_pos
# -- apply action to the robot
scene["robot"].set_joint_position_target(targets)
# -- write data to sim
scene.write_data_to_sim()
# perform step
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
# update buffers
robot.update(sim_dt)
for camera in cameras:
camera.update(dt=sim_dt)
for height_sensor in height_scanner:
height_sensor.update(dt=sim_dt)
for contact_sensor in contact_forces:
contact_sensor.update(dt=sim_dt)
# update camera data and print information
print(cameras[0])
print("Received shape of rgb image: ", cameras[0].data.output["rgb"].shape)
print("Received shape of depth image: ", cameras[0].data.output["distance_to_image_plane"].shape)
scene.update(sim_dt)
# print information from the sensors
print("-------------------------------")
print(scene["camera"])
print("Received shape of rgb image: ", scene["camera"].data.output["rgb"].shape)
print("Received shape of depth image: ", scene["camera"].data.output["distance_to_image_plane"].shape)
print("-------------------------------")
print(height_scanner[0])
print("Received max height value: ", torch.max(height_scanner[0].data.ray_hits_w[..., -1]).item())
print(scene["height_scanner"])
print("Received max height value: ", torch.max(scene["height_scanner"].data.ray_hits_w[..., -1]).item())
print("-------------------------------")
print(contact_forces[0])
print("Received max contact force of: ", torch.max(contact_forces[0].data.net_forces_w).item())
print(scene["contact_forces"])
print("Received max contact force of: ", torch.max(scene["contact_forces"].data.net_forces_w).item())
def main():
"""Main function."""
# Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.01, substeps=1)
sim_cfg = sim_utils.SimulationCfg(dt=0.005, substeps=1)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
# design scene
robot, sensors = design_scene()
scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
scene = InteractiveScene(scene_cfg)
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, robot, sensors)
run_simulator(sim, scene)
if __name__ == "__main__":
......
......@@ -48,39 +48,19 @@ from omni.isaac.orbit.sensors import FrameTransformer, FrameTransformerCfg, Offs
from omni.isaac.orbit.sim import SimulationContext
def design_scene() -> tuple(FrameTransformer, Articulation):
"""Design the scene."""
# Populate scene
# -- Ground-plane
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# -- Lights
cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# -- robot
robot_cfg = ANYMAL_C_CFG
robot_cfg.spawn.func("/World/Anymal_c/Robot", robot_cfg.spawn, translation=(1.5, -1.5, 0.65))
robot = Articulation(robot_cfg.replace(prim_path="/World/Anymal_c/Robot"))
# add frame transformer
frame_transformer = add_sensor()
return frame_transformer, robot
def add_sensor() -> FrameTransformer:
"""Adds FrameTransformer sensor to the scene."""
def define_sensor() -> FrameTransformer:
"""Defines the FrameTransformer sensor to add to the scene."""
# define offset
rot_offset = math_utils.quat_from_euler_xyz(torch.zeros(1), torch.zeros(1), torch.tensor(-math.pi / 2))
pos_offset = math_utils.quat_apply(rot_offset, torch.tensor([0.08795, 0.01305, -0.33797]))
# Example using .* to get full body + LF_FOOT
frame_transformer_cfg = FrameTransformerCfg(
prim_path="/World/Anymal_c/Robot/base",
prim_path="/World/Robot/base",
target_frames=[
FrameTransformerCfg.FrameCfg(prim_path="/World/Anymal_c/Robot/.*"),
FrameTransformerCfg.FrameCfg(prim_path="/World/Robot/.*"),
FrameTransformerCfg.FrameCfg(
prim_path="/World/Anymal_c/Robot/LF_SHANK",
prim_path="/World/Robot/LF_SHANK",
name="LF_FOOT",
offset=OffsetCfg(pos=tuple(pos_offset.tolist()), rot=tuple(rot_offset[0].tolist())),
),
......@@ -92,20 +72,45 @@ def add_sensor() -> FrameTransformer:
return frame_transformer
def run_simulator(sim: sim_utils.SimulationContext, robot: Articulation, frame_transformer: FrameTransformer):
def design_scene() -> dict:
"""Design the scene."""
# Populate scene
# -- Ground-plane
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# -- Lights
cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# -- Robot
robot = Articulation(ANYMAL_C_CFG.replace(prim_path="/World/Robot"))
# -- Sensors
frame_transformer = define_sensor()
# return the scene information
scene_entities = {"robot": robot, "frame_transformer": frame_transformer}
return scene_entities
def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
"""Run the simulator."""
# Define simulation stepping
sim_dt = sim.get_physics_dt()
sim_time = 0.0
count = 0
# extract entities for simplified notation
robot: Articulation = scene_entities["robot"]
frame_transformer: FrameTransformer = scene_entities["frame_transformer"]
# We only want one visualization at a time. This visualizer will be used
# to step through each frame so the user can verify that the correct frame
# is being visualized as the frame names are printing to console
if not args_cli.headless:
cfg = FRAME_MARKER_CFG.replace(prim_path="/Visuals/FrameVisualizerFromScript")
cfg.markers["frame"].scale = (0.05, 0.05, 0.05)
cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
transform_visualizer = VisualizationMarkers(cfg)
else:
transform_visualizer = None
frame_index = 0
# Simulate physics
......@@ -126,10 +131,10 @@ def run_simulator(sim: sim_utils.SimulationContext, robot: Articulation, frame_t
# are correctly associated with the frames
if not args_cli.headless:
if count % 50 == 0:
# get frame names
frame_names = frame_transformer.data.target_frame_names
frame_name = frame_names[frame_index]
print(f"Displaying {frame_index}: {frame_name}")
print(f"Displaying Frame ID {frame_index}: {frame_names[frame_index]}")
# increment frame index
frame_index += 1
frame_index = frame_index % len(frame_names)
......@@ -146,13 +151,13 @@ def main():
# Set main camera
sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# Design the scene
frame_transformer, robot = design_scene()
scene_entities = design_scene()
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, robot, frame_transformer)
run_simulator(sim, scene_entities)
if __name__ == "__main__":
......
......@@ -38,7 +38,7 @@ import torch
import traceback
import carb
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import RigidObject, RigidObjectCfg
......@@ -47,7 +47,22 @@ from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.orbit.utils.timer import Timer
def design_scene():
def define_sensor() -> RayCaster:
"""Defines the ray-caster sensor to add to the scene."""
# Create a ray-caster sensor
ray_caster_cfg = RayCasterCfg(
prim_path="/World/Origin.*/ball",
mesh_prim_paths=["/World/ground"],
pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=(2.0, 2.0)),
attach_yaw_only=True,
debug_vis=not args_cli.headless,
)
ray_caster = RayCaster(cfg=ray_caster_cfg)
return ray_caster
def design_scene() -> dict:
"""Design the scene."""
# Populate scene
# -- Rough terrain
......@@ -56,46 +71,37 @@ def design_scene():
# -- Light
cfg = sim_utils.DistantLightCfg(intensity=2000)
cfg.func("/World/light", cfg)
# Create separate groups called "Origin1", "Origin2", "Origin3"
# Each group will have a robot in it
origins = [[0.25, 0.25, 0.0], [-0.25, 0.25, 0.0], [0.25, -0.25, 0.0], [-0.25, -0.25, 0.0]]
for i, origin in enumerate(origins):
prim_utils.create_prim(f"/World/Origin{i}", "Xform", translation=origin)
# -- Balls
cfg = sim_utils.SphereCfg(
radius=0.25,
rigid_props=sim_utils.RigidBodyPropertiesCfg(),
mass_props=sim_utils.MassPropertiesCfg(mass=0.5),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)),
cfg = RigidObjectCfg(
prim_path="/World/Origin.*/ball",
spawn=sim_utils.SphereCfg(
radius=0.25,
rigid_props=sim_utils.RigidBodyPropertiesCfg(),
mass_props=sim_utils.MassPropertiesCfg(mass=0.5),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)),
),
)
cfg.func("/World/envs/env_0/ball", cfg)
cfg.func("/World/envs/env_1/ball", cfg)
cfg.func("/World/envs/env_2/ball", cfg)
cfg.func("/World/envs/env_3/ball", cfg)
# Setup rigid object
cfg = RigidObjectCfg(prim_path="/World/envs/env_.*/ball")
# Create rigid object handler
balls = RigidObject(cfg)
# -- Sensors
ray_caster = define_sensor()
# Create a ray-caster sensor
ray_caster = add_sensor()
return ray_caster, balls
def add_sensor():
# Create a ray-caster sensor
ray_caster_cfg = RayCasterCfg(
prim_path="/World/envs/env_.*/ball",
mesh_prim_paths=["/World/ground"],
pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=(1.6, 1.0)),
attach_yaw_only=True,
debug_vis=not args_cli.headless,
)
ray_caster = RayCaster(cfg=ray_caster_cfg)
return ray_caster
# return the scene information
scene_entities = {"balls": balls, "ray_caster": ray_caster}
return scene_entities
def run_simulator(sim: sim_utils.SimulationContext, ray_caster: RayCaster, balls: RigidObject):
def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
"""Run the simulator."""
# Extract scene_entities for simplified notation
ray_caster: RayCaster = scene_entities["ray_caster"]
balls: RigidObject = scene_entities["balls"]
# define an initial position of the sensor
ball_default_state = balls.data.default_root_state.clone()
......@@ -131,15 +137,15 @@ def main():
sim_cfg = sim_utils.SimulationCfg()
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
set_camera_view([0.0, 15.0, 15.0], [0.0, 0.0, -2.5])
sim.set_camera_view([0.0, 15.0, 15.0], [0.0, 0.0, -2.5])
# Design the scene
ray_caster, balls = design_scene()
scene_entities = design_scene()
# Play simulator
sim.reset()
# Print the sensor information
print(ray_caster)
# Now we are ready!
print("[INFO]: Setup complete...")
# Run simulator
run_simulator(sim=sim, ray_caster=ray_caster, balls=balls)
run_simulator(sim=sim, scene_entities=scene_entities)
if __name__ == "__main__":
......
......@@ -19,14 +19,13 @@ The camera sensor is based on using Warp kernels which do ray-casting against st
import argparse
# omni-isaac-orbit
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="This script demonstrates how to use the ray-cast camera sensor.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--num_envs", type=int, default=16, help="Number of environments to generate.")
parser.add_argument("--save", type=int, default=16, help="Number of environments to generate.")
parser.add_argument("--save", action="store_true", default=False, help="Save the obtained data to disk.")
args_cli = parser.parse_args()
# launch omniverse app
......@@ -51,29 +50,19 @@ from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.orbit.utils.math import project_points, unproject_depth
def design_scene():
# Populate scene
# -- Rough terrain
cfg = sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd")
cfg.func("/World/ground", cfg)
# Lights
cfg = sim_utils.DistantLightCfg(intensity=600.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# add and return sensor and terrain
return add_sensor()
def add_sensor():
def define_sensor() -> RayCasterCamera:
"""Defines the ray-cast camera sensor to add to the scene."""
# Camera base frames
prim_utils.create_prim("/World/CameraSensor_00", "Xform")
prim_utils.create_prim("/World/CameraSensor_01", "Xform")
# In contras to the USD camera, we associate the sensor to the prims at these locations.
# This means that parent prim of the sensor is the prim at this location.
prim_utils.create_prim("/World/Origin_00/CameraSensor", "Xform")
prim_utils.create_prim("/World/Origin_01/CameraSensor", "Xform")
# Setup camera sensor
camera_cfg = RayCasterCameraCfg(
prim_path="/World/CameraSensor_.*",
prim_path="/World/Origin_.*/CameraSensor",
mesh_prim_paths=["/World/ground"],
update_period=0,
update_period=0.1,
offset=RayCasterCameraCfg.OffsetCfg(pos=(0.0, 0.0, 0.0), rot=(1.0, 0.0, 0.0, 0.0)),
data_types=["distance_to_image_plane", "normals", "distance_to_camera"],
debug_vis=True,
......@@ -90,14 +79,31 @@ def add_sensor():
return camera
def run_simulator(sim: sim_utils.SimulationContext, camera: RayCasterCamera):
def design_scene():
# Populate scene
# -- Rough terrain
cfg = sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd")
cfg.func("/World/ground", cfg)
# -- Lights
cfg = sim_utils.DistantLightCfg(intensity=600.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# -- Sensors
camera = define_sensor()
# return the scene information
scene_entities = {"camera": camera}
return scene_entities
def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
"""Run the simulator."""
# extract entities for simplified notation
camera: RayCasterCamera = scene_entities["camera"]
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "ray_caster_camera")
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Play simulator
sim.reset()
# Set pose: There are two ways to set the pose of the camera.
# -- Option-1: Set pose using view
eyes = torch.tensor([[2.5, 2.5, 2.5], [-2.5, -2.5, 2.5]], device=sim.device)
......@@ -106,7 +112,7 @@ def run_simulator(sim: sim_utils.SimulationContext, camera: RayCasterCamera):
# -- Option-2: Set pose using ROS
# position = torch.tensor([[2.5, 2.5, 2.5]], device=sim.device)
# orientation = torch.tensor([[-0.17591989, 0.33985114, 0.82047325, -0.42470819]], device=sim.device)
# camera.set_world_pose_ros(position, orientation, indices=[0])
# camera.set_world_poses(position, orientation, indices=[0], convention="ros")
# Simulate physics
while simulation_app.is_running():
......@@ -168,13 +174,13 @@ def main():
# Set main camera
sim.set_camera_view([2.5, 2.5, 3.5], [0.0, 0.0, 0.0])
# design the scene
camera = design_scene()
scene_entities = design_scene()
# Play simulator
sim.play()
# Print the sensor information
print(camera)
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run simulator
run_simulator(sim=sim, camera=camera)
run_simulator(sim=sim, scene_entities=scene_entities)
if __name__ == "__main__":
......
......@@ -22,7 +22,6 @@ from __future__ import annotations
import argparse
# omni-isaac-orbit
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
......@@ -64,6 +63,29 @@ from omni.isaac.orbit.utils.math import project_points, transform_points, unproj
draw_interface = omni_debug_draw.acquire_debug_draw_interface()
def define_sensor() -> Camera:
"""Defines the camera sensor to add to the scene."""
# Setup camera sensor
# In contras to the ray-cast camera, we spawn the prim at these locations.
# This means the camera sensor will be attached to these prims.
prim_utils.create_prim("/World/Origin_00", "Xform")
prim_utils.create_prim("/World/Origin_01", "Xform")
camera_cfg = CameraCfg(
prim_path="/World/Origin_.*/CameraSensor",
update_period=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
)
# Create camera
camera = Camera(cfg=camera_cfg)
return camera
def design_scene():
"""Design the scene."""
# Populate scene
......@@ -99,32 +121,19 @@ def design_scene():
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
# add and return sensor
return add_sensor()
# Sensors
camera = define_sensor()
# return the scene information
scene_entities = {"camera": camera}
return scene_entities
def add_sensor():
# Setup camera sensor
prim_utils.create_prim("/World/CameraSensor_00", "Xform")
prim_utils.create_prim("/World/CameraSensor_01", "Xform")
camera_cfg = CameraCfg(
prim_path="/World/CameraSensor_.*/Cam",
update_period=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
)
# Create camera
camera = Camera(cfg=camera_cfg)
return camera
def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
"""Run the simulator."""
# extract entities for simplified notation
camera: Camera = scene_entities["camera"]
def run_simulator(sim: sim_utils.SimulationContext, camera: Camera):
"""Run simulator."""
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
......@@ -137,7 +146,7 @@ def run_simulator(sim: sim_utils.SimulationContext, camera: Camera):
# -- Option-2: Set pose using ROS
# position = torch.tensor([[2.5, 2.5, 2.5]], device=sim.device)
# orientation = torch.tensor([[-0.17591989, 0.33985114, 0.82047325, -0.42470819]], device=sim.device)
# camera.set_world_pose_ros(position, orientation, indices=[0])
# camera.set_world_poses(position, orientation, env_ids=[0], convention="ros")
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
......@@ -150,7 +159,7 @@ def run_simulator(sim: sim_utils.SimulationContext, camera: Camera):
# Step simulation
sim.step()
# Update camera data
camera.update(dt=0.0)
camera.update(dt=sim.get_physics_dt())
# Print camera info
print(camera)
......@@ -182,6 +191,7 @@ def run_simulator(sim: sim_utils.SimulationContext, camera: Camera):
else:
rep_output[key] = data
# Save images
# Note: We need to provide On-time data for Replicator to save the images.
rep_output["trigger_outputs"] = {"on_time": camera.frame[camera_index]}
rep_writer.write(rep_output)
......@@ -230,11 +240,13 @@ def main():
# Set main camera
sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# design the scene
camera = design_scene()
scene_entities = design_scene()
# Play simulator
sim.play()
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run simulator
run_simulator(sim, camera)
run_simulator(sim, scene_entities)
if __name__ == "__main__":
......
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