isaac-sim / IsaacLab

Unified framework for robot learning built on NVIDIA Isaac Sim
https://isaac-sim.github.io/IsaacLab
Other
1.83k stars 685 forks source link

[Question] Camera addition on Franka Hand #99

Closed kumar-sanjeeev closed 1 year ago

kumar-sanjeeev commented 1 year ago

Question

I am trying to create an environment where I need to add two cameras to the Franka Panda Hand, one looking at the target from the left and the other from the right. I tried to achieve this by adding the camera sensor as a child to the panda hand. I thought that as the panda hand moves, the camera would also move with it, as they have a child-parent relation. However, it does not behave in the same way I thought; the camera's position and orientation don't change as the panda hand moves in the environment. To make this work, I updated the position of the camera with the current end-effector position after each physics step. I am attaching the script I used for this work as a reference.

Do we have any examples in the current available release version where the camera is mounted on the panda hand and moves along with it ?

import argparse

from omni.isaac.kit import SimulationApp

# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--robot", type=str, default="franka_panda", help="Name of the robot.")
args_cli = parser.parse_args()

# launch omniverse app
config = {"headless": args_cli.headless}
simulation_app = SimulationApp(config)

"""Rest everything follows."""

import torch

import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.core.utils.carb import set_carb_setting

import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.robots.config.franka import FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG
from omni.isaac.orbit.robots.config.universal_robots import UR10_CFG
from omni.isaac.orbit.robots.single_arm import SingleArmManipulator
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR

# imports for camera usuage
from omni.isaac.orbit.sensors.camera import Camera, PinholeCameraCfg
"""
Main
"""

def main():
    """Spawns a single arm manipulator and applies random joint commands."""

    # Load kit helper
    sim = SimulationContext(physics_dt=0.01, rendering_dt=0.01, backend="torch", device="cuda")
    # Set main camera
    set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])

    ############# changes
    # Enable fltacache which avoids passing data over to USD structure
    # this speed up the read-write operation of GPU buffers
    if sim.get_physics_context().use_gpu_pipeline:
        sim.get_physics_context().enable_flatcache(True)
    # Enable hydra scene-graph instancing
    # this is needed to visualize the scene when flatcache is enabled
    set_carb_setting(sim._settings, "/persistent/omnihydra/useSceneGraphInstancing", True)
    ###############

    # Spawn things into stage
    # Ground-plane
    kit_utils.create_ground_plane("/World/defaultGroundPlane", z_position=-1.05)
    # Lights-1
    prim_utils.create_prim(
        "/World/Light/GreySphere",
        "SphereLight",
        translation=(4.5, 3.5, 10.0),
        attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
    )
    # Lights-2
    prim_utils.create_prim(
        "/World/Light/WhiteSphere",
        "SphereLight",
        translation=(-4.5, 3.5, 10.0),
        attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
    )
    # Table
    table_usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd"
    prim_utils.create_prim("/World/Table_1", usd_path=table_usd_path, translation=(0.55, -1.0, 0.0))
    # Robots
    # -- Resolve robot config from command-line arguments
    if args_cli.robot == "franka_panda":
        robot_cfg = FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG
    elif args_cli.robot == "ur10":
        robot_cfg = UR10_CFG
    else:
        raise ValueError(f"Robot {args_cli.robot} is not supported. Valid: franka_panda, ur10")
    # -- Spawn robot
    robot = SingleArmManipulator(cfg=robot_cfg)
    robot.spawn("/World/Robot_1", translation=(0.0, -1.0, 0.0))
    # Hand Camera
    # -- camera cfg
    camera_cfg = PinholeCameraCfg(
        sensor_tick=0,
        height=480,
        width=640,
        data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors"],
        usd_params=PinholeCameraCfg.UsdCameraCfg(
            focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
        ),
    )
    # -- camera Instance
    hand_camera = Camera(
        cfg=camera_cfg,
        device="cuda"
    )
    # -- Spawn camera
    hand_camera.spawn("/World/Robot_1/panda_hand/hand_camera")

    # Play the simulator
    sim.reset()
    # Acquire handles
    # Initialize handles
    robot.initialize("/World/Robot.*")
    hand_camera.initialize()
    # Reset states
    robot.reset_buffers()

    # Now we are ready!
    print("[INFO]: Setup complete...")

    # dummy actions
    actions = torch.rand(robot.count, robot.num_actions, device=robot.device)
    has_gripper = robot.cfg.meta_info.tool_num_dof > 0

    # Define simulation stepping
    sim_dt = sim.get_physics_dt()
    # episode counter
    sim_time = 0.0
    ep_step_count = 0
    # Simulate physics
    while simulation_app.is_running():
        # If simulation is stopped, then exit.
        if sim.is_stopped():
            break
        # If simulation is paused, then skip.
        if not sim.is_playing():
            sim.step(render=not args_cli.headless)
            continue
        # reset
        if ep_step_count % 1000 == 0:
            sim_time = 0.0
            ep_step_count = 0
            # reset dof state
            dof_pos, dof_vel = robot.get_default_dof_state()
            robot.set_dof_state(dof_pos, dof_vel)
            robot.reset_buffers()
            # reset command
            actions = torch.rand(robot.count, robot.num_actions, device=robot.device)
            # reset gripper
            if has_gripper:
                actions[:, -1] = -1
            print("[INFO]: Resetting robots state...")
        # change the gripper action
        if ep_step_count % 200 == 0 and has_gripper:
            # flip command for the gripper
            actions[:, -1] = -actions[:, -1]
            print(f"[INFO]: [Step {ep_step_count:03d}]: Flipping gripper command...")
        # apply action to the robot
        robot.apply_action(actions)
        ee_pos = robot.data.ee_state_w[0, 0:3]
        ee_orient = robot.data.ee_state_w[0, 3:7]
        ee_pos_list = ee_pos.cpu().tolist()
        ee_orient_list = ee_orient.cpu().tolist()
        hand_camera.set_world_pose_ros(ee_pos_list, [1, 0, 0, 0])
        # perform step
        sim.step()
        # update sim-time
        sim_time += sim_dt
        ep_step_count += 1
        # note: to deal with timeline events such as stopping, we need to check if the simulation is playing
        if sim.is_playing():
            # update buffers
            robot.update_buffers(sim_dt)

if __name__ == "__main__":
    # Run the main function
    main()
    # Close the simulator
    simulation_app.close()
Mayankm96 commented 1 year ago

Thank you for the repro.

From my investigation, it is moving around with the robot. However, you haven't set a transform from the hand frame to the camera frame. because of this the sensor is inside the hand mesh and you only see black pixels.

I changed the spawn call to the following and it works as expected:

hand_camera.spawn("/World/Robot_1/panda_hand/hand_camera", translation=(0.0, 0.0, 0.5))

You can switch the viewport to show your camera (tutorial here). With the above line change, I see the following:

https://github.com/NVIDIA-Omniverse/Orbit/assets/12863862/2d87f08e-9bf1-4e0b-9b35-82148b505724

kumar-sanjeeev commented 1 year ago

Hi @Mayankm96

Thanks for replying to my query. I tried what you suggested, its works :)