Why does the render_dt influence the pickplace controller/task

Dear all,

I have been using Isaac Sim 2022.2.1 for a few weeks now and am currently working on achieving a pick-and-place simulation with a high frame rate, not necessarily in real-time. The setup appears to be functioning well so far, but I am encountering challenges in controlling the parameters physics_dt, render_dt, and time_codes_per_second in combination with the omni.isaac.franka.controllers.PickplaceController.

My goal is to achieve a frame rate of 300 with 600 physics steps and also 600 time codes per second to synchronize the simulation time with the frames per second. I am attempting to control these parameters as follows:

world = World(physics_dt=1.0 / 600.0, rendering_dt=1.0 / 300.0)
timeline.set_time_codes_per_second(600)

When I add callbacks for physics steps and render steps, I get the expected results with one rendering per two physics steps.
But if I check the timeline via timeline.get_current_time() on every physics step and rendering step every rendering step and the next two physics steps share the same time before it gets updated in the next rendering step.
What I expected is a unique time for every step, no matter if physics or rendering.

However, the real issue arises when executing the pick-and-place task. With rendering_dt=60, everything works fine. Still, when I increase the rendering_dt, the arm starts to move but attempts to grasp the object even before reaching it and continues initiating the placing action without holding the object.

It seems like the controller is executing a fixed number of steps without considering simulation time. Even then, I am puzzled as to why it reacts to rendering_dt and not physics_dt.

I would greatly appreciate any assistance in resolving this issue.

UPDATE: same behavior in Isaac Sim 2023.1.0-Hotfix.1

Here the code to reproduce:

from omni.isaac.kit import SimulationApp

sim_app_config = {
    "headless": True,
    "renderer": "RayTracedLighting"
}

simulation_app = SimulationApp(sim_app_config)

from omni.isaac.core import World
from omni.timeline import get_timeline_interface
from omni.isaac.franka.tasks import PickPlace
from omni.isaac.franka.controllers import PickPlaceController


def check_timeline(last_sec=0, fr_counter=0):
    if int(_timeline.get_current_time()) > last_sec:
        print(f"++++++++++ framerate of second {int(last_sec)} {fr_counter} ++++++++++")
        last_sec = int(_timeline.get_current_time())
        fr_counter = 1
    else:
        fr_counter += 1
    return last_sec, fr_counter

def on_physics_step(event):
    print('physics step', _timeline.get_current_time())
    pass

def on_render_step(event):
    print('render step', _timeline.get_current_time())
    pass


_timeline = get_timeline_interface()
_world = World(physics_dt=1.0 / 600.0, rendering_dt=1.0 / 300.0)  
_timeline.set_time_codes_per_second(600)
_world.add_physics_callback('physics callback', on_physics_step)
_world.add_render_callback('render callback', on_render_step)

_task = PickPlace(name="easy task")
_world.add_task(_task)
_world.reset()
_task_params = _world.get_task("easy task").get_params()
_franka = _world.scene.get_object(_task_params["robot_name"]["value"])
_cube_name = _task_params["cube_name"]["value"]
_controller = PickPlaceController(
    name="pick_place_controller",
    gripper=_franka.gripper,
    robot_articulation=_franka,
)

last_sec = 0
fr_counter = 0
while simulation_app.is_running():
    _world.step(render=True)
    last_sec, fr_counter = check_timeline(last_sec, fr_counter)
    current_observations = _world.get_observations()
    actions = _controller.forward(
        picking_position=current_observations[_cube_name]["position"],
        placing_position=current_observations[_cube_name]["target_position"],
        current_joint_positions=current_observations[_franka.name]["joint_positions"],
    )
    _franka.apply_action(actions)

Hi, is there nobody who can help me with this problem?

I played around with it a bit more and moved things to the render and physics callbacks to have a clear separation but at the end I’m still getting the same results.

I would really appreciate any help!

Best
Thilo

Hi Thilo,

Apologies for the delay in our response. There are few things that can help in understanding the current behaviour you are seeing.

  • The only time for Isaac Sim is the physics time which you can get through the world.current_time and the number of physics steps executed through world.current_time_step_index
  • The time you get from omni.timeline interface you can’t rely on it since its a different time used for USD animation
  • When rendering is faster than physics, each step(render=True) will not necessarily execute a physics step that’s why time will sometime stay the same after stepping since physics is not executed in this case.
  • The pick and place controller provided is meant for tutorials purposes (a toy controller) to help you get started, its not a reliable and robust controller by any means (the idea was to have a minimal simple example for the users to start tinkering with their robots)
  • The controller does have its own timeline which is stepped everytime a forward call is executed. To have the same behavior regardless of faster rendering you need to make sure that the forward call is executed every physics step, otherwise you should change the events_dt in the controller which is a parameter that you can overwrite.

Below is the pick place example shipped with faster rendering for your reference.

 # Copyright (c) 2021-2023, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#
from omni.isaac.kit import SimulationApp

simulation_app = SimulationApp({"headless": False})

import numpy as np
from omni.isaac.core import World
from omni.isaac.franka.controllers.pick_place_controller import PickPlaceController
from omni.isaac.franka.tasks import PickPlace

my_world = World(stage_units_in_meters=1.0, rendering_dt= 1 / 300)
my_task = PickPlace()
my_world.add_task(my_task)
my_world.reset()
task_params = my_task.get_params()
my_franka = my_world.scene.get_object(task_params["robot_name"]["value"])
my_controller = PickPlaceController(
    name="pick_place_controller", gripper=my_franka.gripper, robot_articulation=my_franka
)
articulation_controller = my_franka.get_articulation_controller()

i = 0
current_physics_time = -1
while simulation_app.is_running():
    my_world.step(render=True)
    if my_world.is_playing():
        if my_world.current_time_step_index == 0:
            my_world.reset()
            my_controller.reset()
        if my_world.current_time > current_physics_time:
            current_physics_time = my_world.current_time
            observations = my_world.get_observations()
            actions = my_controller.forward(
                picking_position=observations[task_params["cube_name"]["value"]]["position"],
                placing_position=observations[task_params["cube_name"]["value"]]["target_position"],
                current_joint_positions=observations[task_params["robot_name"]["value"]]["joint_positions"],
                end_effector_offset=np.array([0, 0.005, 0]),
            )
            articulation_controller.apply_action(actions)
        if my_controller.is_done():
            print("done picking and placing")
            
simulation_app.close()

Let us know if you have more questions.

Hi oahmed,

thanks a lot for your reply and the given explanations.

The only time for Isaac Sim is the physics time which you can get through the world.current_time and the number of physics steps executed through world.current_time_step_index

I think the concepts of world.current_time and world.current_time_step_index are clear to me now.

The time you get from omni.timeline interface you can’t rely on it since its a different time used for USD animation

I understand that I should discard the timeline interface for my purposes.

When rendering is faster than physics, each step(render=True) will not necessarily execute a physics step that’s why time will sometime stay the same after stepping since physics is not executed in this case.

The part about the fast rendering and the not executed physics steps I understand to some point. And if I understand it correctly the checking of the my_world.current_time > current_physics_time is a way to differentiate between a rendering step without physics and one with physics?

The pick and place controller provided is meant for tutorials purposes (a toy controller) to help you get started, its not a reliable and robust controller by any means (the idea was to have a minimal simple example for the users to start tinkering with their robots)

The pickplace controller will not be my controller in the long run.

The controller does have its own timeline which is stepped everytime a forward call is executed. To have the same behavior regardless of faster rendering you need to make sure that the forward call is executed every physics step, otherwise you should change the events_dt in the controller which is a parameter that you can overwrite.

Does that mean, the controller has a fixed number of steps? And about the events_dt, I did have a look into that at some point but I did not really understand how it works. Is there a tutorial or explanation page to it, I could not find a proper one.

But I’m still confused I think.
To make myself clear, my goal is to generate frames with a very high rate and to have the robot arm make a grasp in moves that are, in the best case even smaller than the frame rate to have a smooth motion, or at least as small as the frame rate.
I’m generating my frames with the replicator extensions and what I want is something like the following:
I want 600 steps per second
with every step

  • the world-time increases
  • the arm makes a step
  • every 2nd step an image is generated
    I do not care about the computation time or real-time

If I understand your example correct with increasing the rendering_dt = 1/300 when setting the World instance, the number of steps in the while loop is increased but most of those steps are just passing by without any change. When I generate frames out of it for every step that is made, I’m getting 3-4 frames that are showing the same until there is change. Sure I can also just create the frames when an action is applied to the controller, but then I’m ending up having the same amount of frames in the same amount of time as I have when setting the rendering_dt=1/60.
Am I missing something here?

Best
Thilo