Unverified Commit 79fec2ff authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fixes tutorials on rigid objects and articulations (#280)

# Description

This MR simplifies the current tutorials on rigid objects and
articulations. It introduces the rigid object first as that is a simpler
example. The articulation builds on top of that tutorial to explain the
joints-related details.

## Type of change

- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent dc2281a7
.. _actuators-guide: .. _feature-actuators:
Actuators Actuators
========= =========
......
.. _how-to-create-articulation-config:
Creating an Articulation Creating an Articulation
======================== ========================
...@@ -127,7 +129,7 @@ Defining the Cartpole's Actuators ...@@ -127,7 +129,7 @@ Defining the Cartpole's Actuators
The cartpole articulation has two actuators, one corresponding to each joint The cartpole articulation has two actuators, one corresponding to each joint
``cart_to_pole`` and ``slider_to_cart``. for more details on actuators, see ``cart_to_pole`` and ``slider_to_cart``. for more details on actuators, see
:ref:`actuators-guide`. :ref:`feature-actuators`.
.. literalinclude:: ../../../../source/extensions/omni.isaac.orbit/omni/isaac/orbit/assets/config/cartpole.py .. literalinclude:: ../../../../source/extensions/omni.isaac.orbit/omni/isaac/orbit/assets/config/cartpole.py
:language: python :language: python
......
Create an empty scene Creating an empty scene
===================== =======================
.. currentmodule:: omni.isaac.orbit .. currentmodule:: omni.isaac.orbit
......
.. _how_to_spawn_objects_label: .. _tutorial-spawn-prims:
Spawn prims into the scene
========================== Spawning prims into the scene
=============================
.. currentmodule:: omni.isaac.orbit .. currentmodule:: omni.isaac.orbit
...@@ -16,11 +17,12 @@ The Code ...@@ -16,11 +17,12 @@ The Code
The tutorial corresponds to the ``prims.py`` script in the ``orbit/source/standalone/tutorials/00_sim`` directory. The tutorial corresponds to the ``prims.py`` script in the ``orbit/source/standalone/tutorials/00_sim`` directory.
Let's take a look at the Python script: Let's take a look at the Python script:
.. dropdown:: :fa:`eye,mr-1` Code for `prims.py` .. dropdown:: Code for prims.py
:icon: code
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py .. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py
:language: python :language: python
:emphasize-lines: 43-79 :emphasize-lines: 43-82, 95
:linenos: :linenos:
...@@ -135,7 +137,7 @@ default to the default values set by USD Physics. ...@@ -135,7 +137,7 @@ default to the default values set by USD Physics.
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py .. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py
:language: python :language: python
:lines: 67-76 :lines: 67-78
:linenos: :linenos:
:lineno-start: 67 :lineno-start: 67
...@@ -149,9 +151,9 @@ All of this information is stored in its USD file. ...@@ -149,9 +151,9 @@ All of this information is stored in its USD file.
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py .. literalinclude:: ../../../../source/standalone/tutorials/00_sim/prims.py
:language: python :language: python
:lines: 78-80 :lines: 80-82
:linenos: :linenos:
:lineno-start: 78 :lineno-start: 80
The table above is added as a reference to the scene. In layman terms, this means that the table is not actually added The table above is added as a reference to the scene. In layman terms, this means that the table is not actually added
to the scene, but a `pointer` to the table asset is added. This allows us to modify the table asset and have the changes to the scene, but a `pointer` to the table asset is added. This allows us to modify the table asset and have the changes
......
...@@ -86,7 +86,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: ...@@ -86,7 +86,7 @@ def design_scene() -> tuple[dict, list[list[float]]]:
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor): def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor):
"""Runs the simulator by applying actions to the robot at every time-step""" """Runs the simulation loop."""
# Define simulation stepping # Define simulation stepping
sim_dt = sim.get_physics_dt() sim_dt = sim.get_physics_dt()
sim_time = 0.0 sim_time = 0.0
......
...@@ -93,8 +93,7 @@ def spawn_markers(): ...@@ -93,8 +93,7 @@ def spawn_markers():
def main(): def main():
"""Spawns lights in the stage and sets the camera view.""" """Main function."""
# Load kit helper # Load kit helper
sim = SimulationContext(sim_utils.SimulationCfg(dt=0.01, substeps=1)) sim = SimulationContext(sim_utils.SimulationCfg(dt=0.01, substeps=1))
# Set main camera # Set main camera
......
...@@ -102,7 +102,7 @@ def design_scene() -> tuple[dict, list[list[float]]]: ...@@ -102,7 +102,7 @@ def design_scene() -> tuple[dict, list[list[float]]]:
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor): def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor):
"""Runs the simulator by applying actions to the robot at every time-step""" """Runs the simulation loop."""
# Define simulation stepping # Define simulation stepping
sim_dt = sim.get_physics_dt() sim_dt = sim.get_physics_dt()
sim_time = 0.0 sim_time = 0.0
......
...@@ -3,7 +3,13 @@ ...@@ -3,7 +3,13 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
"""This script demonstrates how to define and spawn a Cartpole Articulation """This script demonstrates how to spawn a cart-pole and interact with it.
.. code-block:: bash
# Usage
./orbit.sh -p source/standalone/tutorials/01_assets/articulation.py
""" """
from __future__ import annotations from __future__ import annotations
...@@ -16,9 +22,7 @@ import argparse ...@@ -16,9 +22,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser( parser = argparse.ArgumentParser(description="This script demonstrates how to spawn and interact with an articulation.")
description="This script demonstrates how to define and spawn a Cartpole Articulation."
)
# append AppLauncher cli args # append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser) AppLauncher.add_app_launcher_args(parser)
# parse the arguments # parse the arguments
...@@ -28,6 +32,8 @@ args_cli = parser.parse_args() ...@@ -28,6 +32,8 @@ args_cli = parser.parse_args()
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app simulation_app = app_launcher.app
"""Rest everything follows."""
import torch import torch
import traceback import traceback
...@@ -46,17 +52,21 @@ def design_scene() -> tuple[dict, list[list[float]]]: ...@@ -46,17 +52,21 @@ def design_scene() -> tuple[dict, list[list[float]]]:
cfg = sim_utils.GroundPlaneCfg() cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg) cfg.func("/World/defaultGroundPlane", cfg)
# Lights # Lights
cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)) cfg = sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg) cfg.func("/World/Light", cfg)
# Create separate groups called "Origin1", "Origin2", "Origin3" # Create separate groups called "Origin1", "Origin2", "Origin3"
# Each group will have a mount and a robot on top of it # Each group will have a robot in it
origins = [[0.0, 1.0, 0.0]] origins = [[0.0, 0.0, 0.0], [-1.0, 0.0, 0.0]]
# Origin 1
# Origin 1 with Cartpole prim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
prim_utils.create_prim("/World/Origin", "Xform", translation=origins[0]) # Origin 2
# -- Articulation prim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1])
cartpole = Articulation(cfg=CARTPOLE_CFG.replace(prim_path="/World/Robot"))
# Articulation
cartpole_cfg = CARTPOLE_CFG.copy()
cartpole_cfg.prim_path = "/World/Origin.*/Robot"
cartpole = Articulation(cfg=cartpole_cfg)
# return the scene information # return the scene information
scene_entities = {"cartpole": cartpole} scene_entities = {"cartpole": cartpole}
...@@ -64,7 +74,11 @@ def design_scene() -> tuple[dict, list[list[float]]]: ...@@ -64,7 +74,11 @@ def design_scene() -> tuple[dict, list[list[float]]]:
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor): def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor):
"""Runs the simulator by applying actions to the articulation at every time-step""" """Runs the simulation loop."""
# Extract scene entities
# note: we only do this here for readability. In general, it is better to access the entities directly from
# the dictionary. This dictionary is replaced by the InteractiveScene class in the next tutorial.
robot = entities["cartpole"]
# Define simulation stepping # Define simulation stepping
sim_dt = sim.get_physics_dt() sim_dt = sim.get_physics_dt()
count = 0 count = 0
...@@ -75,43 +89,41 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula ...@@ -75,43 +89,41 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula
# reset counter # reset counter
count = 0 count = 0
# reset the scene entities # reset the scene entities
for index, robot in enumerate(entities.values()): # root state
# root state # we offset the root state by the origin since the states are written in simulation world frame
# 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
# if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world root_state = robot.data.default_root_state.clone()
root_state = robot.data.default_root_state.clone() root_state[:, :3] += origins
root_state[:, :3] += origins[index] robot.write_root_state_to_sim(root_state)
robot.write_root_state_to_sim(root_state) # set joint positions with some noise
# set joint positions with some noise joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone()
joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone() joint_pos += torch.rand_like(joint_pos) * 0.1
joint_pos += torch.rand_like(joint_pos) * 0.1 robot.write_joint_state_to_sim(joint_pos, joint_vel)
robot.write_joint_state_to_sim(joint_pos, joint_vel) # clear internal buffers
# clear internal buffers robot.reset()
robot.reset()
print("[INFO]: Resetting robot state...") print("[INFO]: Resetting robot state...")
# Apply random action # Apply random action
for robot in entities.values(): # -- generate random joint efforts
# generate random joint efforts efforts = torch.randn_like(robot.data.joint_pos) * 5.0
efforts = torch.randn_like(robot.data.joint_pos) * 5.0 # -- apply action to the robot
# apply action to the robot robot.set_joint_effort_target(efforts)
robot.set_joint_effort_target(efforts) # -- write data to sim
# write data to sim robot.write_data_to_sim()
robot.write_data_to_sim()
# Perform step # Perform step
sim.step() sim.step()
# Increment counter # Increment counter
count += 1 count += 1
# Update buffers # Update buffers
for robot in entities.values(): robot.update(sim_dt)
robot.update(sim_dt)
def main(): def main():
"""Main function."""
# Load kit helper # Load kit helper
sim_cfg = sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False) sim_cfg = sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False)
sim = SimulationContext(sim_cfg) sim = SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view([2.5, 1.0, 4.0], [0.0, 1.0, 2.0]) sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
# Design scene # Design scene
scene_entities, scene_origins = design_scene() scene_entities, scene_origins = design_scene()
scene_origins = torch.tensor(scene_origins, device=sim.device) scene_origins = torch.tensor(scene_origins, device=sim.device)
......
...@@ -39,12 +39,12 @@ import torch ...@@ -39,12 +39,12 @@ import torch
import traceback import traceback
import carb import carb
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
import omni.isaac.orbit.utils.math as math_utils
from omni.isaac.orbit.assets import RigidObject, RigidObjectCfg from omni.isaac.orbit.assets import RigidObject, RigidObjectCfg
from omni.isaac.orbit.sim import SimulationContext from omni.isaac.orbit.sim import SimulationContext
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.orbit.utils.math import quat_mul, random_yaw_orientation, sample_cylinder
def design_scene(): def design_scene():
...@@ -53,35 +53,41 @@ def design_scene(): ...@@ -53,35 +53,41 @@ def design_scene():
cfg = sim_utils.GroundPlaneCfg() cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg) cfg.func("/World/defaultGroundPlane", cfg)
# Lights # Lights
cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75)) cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.8, 0.8, 0.8))
cfg.func("/World/Light", cfg) cfg.func("/World/Light", cfg)
# add rigid objects and return them
return add_rigid_objects()
# Create separate groups called "Origin1", "Origin2", "Origin3"
def add_rigid_objects(): # Each group will have a robot in it
"""Adds rigid objects to the scene.""" 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]]
# add YCB objects for i, origin in enumerate(origins):
ycb_usd_paths = { prim_utils.create_prim(f"/World/Origin{i}", "Xform", translation=origin)
"crackerBox": f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/003_cracker_box.usd",
"sugarBox": f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/004_sugar_box.usd", # Rigid Object
"tomatoSoupCan": f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/005_tomato_soup_can.usd", cone_cfg = RigidObjectCfg(
"mustardBottle": f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/006_mustard_bottle.usd", prim_path="/World/Origin.*/Cone",
} spawn=sim_utils.ConeCfg(
for key, usd_path in ycb_usd_paths.items(): radius=0.1,
translation = torch.rand(3).tolist() height=0.2,
cfg = sim_utils.UsdFileCfg(usd_path=usd_path) rigid_props=sim_utils.RigidBodyPropertiesCfg(),
cfg.func(f"/World/Objects/{key}", cfg, translation=translation) mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
collision_props=sim_utils.CollisionPropertiesCfg(),
# Setup rigid object visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2),
cfg = RigidObjectCfg(prim_path="/World/Objects/.*") ),
# Create rigid object handler init_state=RigidObjectCfg.InitialStateCfg(),
rigid_object = RigidObject(cfg) )
cone_object = RigidObject(cfg=cone_cfg)
return rigid_object
# return the scene information
scene_entities = {"cone": cone_object}
def run_simulator(sim: sim_utils.SimulationContext, rigid_object: RigidObject): return scene_entities, origins
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, RigidObject], origins: torch.Tensor):
"""Runs the simulation loop."""
# Extract scene entities
# note: we only do this here for readability. In general, it is better to access the entities directly from
# the dictionary. This dictionary is replaced by the InteractiveScene class in the next tutorial.
cone_object = entities["cone"]
# Define simulation stepping # Define simulation stepping
sim_dt = sim.get_physics_dt() sim_dt = sim.get_physics_dt()
sim_time = 0.0 sim_time = 0.0
...@@ -94,45 +100,48 @@ def run_simulator(sim: sim_utils.SimulationContext, rigid_object: RigidObject): ...@@ -94,45 +100,48 @@ def run_simulator(sim: sim_utils.SimulationContext, rigid_object: RigidObject):
sim_time = 0.0 sim_time = 0.0
count = 0 count = 0
# reset root state # reset root state
root_state = rigid_object.data.default_root_state.clone() root_state = cone_object.data.default_root_state.clone()
# -- position # sample a random position on a cylinder around the origins
root_state[:, :3] = sample_cylinder( root_state[:, :3] += origins
radius=0.5, h_range=(0.15, 0.25), size=rigid_object.num_instances, device=rigid_object.device root_state[:, :3] += math_utils.sample_cylinder(
) radius=0.1, h_range=(0.25, 0.5), size=cone_object.num_instances, device=cone_object.device
# -- orientation: apply yaw rotation
root_state[:, 3:7] = quat_mul(
random_yaw_orientation(rigid_object.num_instances, rigid_object.device), root_state[:, 3:7]
) )
# -- set root state # write root state to simulation
rigid_object.write_root_state_to_sim(root_state) cone_object.write_root_state_to_sim(root_state)
# reset buffers # reset buffers
rigid_object.reset() cone_object.reset()
print(">>>>>>>> Reset!") print("----------------------------------------")
print("[INFO]: Resetting object state...")
# apply sim data # apply sim data
rigid_object.write_data_to_sim() cone_object.write_data_to_sim()
# perform step # perform step
sim.step() sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 count += 1
# update buffers # update buffers
rigid_object.update(sim_dt) cone_object.update(sim_dt)
# print the root position
if count % 50 == 0:
print(f"Root position (in world): {cone_object.data.root_state_w[:, :3]}")
def main(): def main():
"""Main function.""" """Main function."""
# Load kit helper # Load kit helper
sim = SimulationContext(sim_utils.SimulationCfg()) sim_cfg = sim_utils.SimulationCfg()
sim = SimulationContext(sim_cfg)
# Set main camera # Set main camera
sim.set_camera_view(eye=[1.5, 1.5, 1.5], target=[0.0, 0.0, 0.0]) sim.set_camera_view(eye=[1.5, 0.0, 1.0], target=[0.0, 0.0, 0.0])
# design scene # Design scene
rigid_object = design_scene() scene_entities, scene_origins = design_scene()
scene_origins = torch.tensor(scene_origins, device=sim.device)
# Play the simulator # Play the simulator
sim.reset() sim.reset()
# Now we are ready! # Now we are ready!
print("[INFO]: Setup complete...") print("[INFO]: Setup complete...")
# Run the simulator # Run the simulator
run_simulator(sim, rigid_object) run_simulator(sim, scene_entities, scene_origins)
if __name__ == "__main__": 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