How to speed up the robot?

Hi, I am testing the robot using Omniverse isaacsim’s Navigation Sample Applications in the link below.
https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/manual_omni_isaac_demos.html#navigation-sample-applications
I’m not trying to use ROS Navigation.

How can I speed up the robot in Navigation Sample Applications?

Even if I change the max speed in the UI, the speed is the same.

Hi @toni.sm
Talk to you in a long time.

I would like to speed up the sample robot of Navigation Sample Applications, transporter or carter, which part of the code should I modify?


The speed does not change even after modifying the code in navigation_preview.py.

How can I change the speed of the robot?
I want to change the speed of the sample robot and then apply it to my robot.

Hi @gudwnzm

You can modify the self._robot_wheels_speed variables (in navigation_preview.py file). This variable is used by the RobotController to “Normalizes both wheels speed if any speed will be clipped” (simple_robot_controller.py)

Note that in Isaac Sim 2022.1.0 distance units are in meters…

            if current_robot_index == 0:
                asset_path = self._assets_root_path + "/Isaac/Robots/Transporter"
                robot_usd = asset_path + "/transporter.usd"
                self._robot_chassis = self._robot_prim_path + "/chassis"
                self._robot_wheels = ["left_wheel_joint", "right_wheel_joint"]
                self._robot_wheels_speed = [3, 3]
                self._wheelbase_Length = 0.56
                self._wheel_radius = 0.085

Hi @toni.sm
Thank you for your quick and kind reply to me.
As you advised, I speeded up the robot by modifying self_robot_wheels_speed and self_rc.control_command.
Thank you.

I have one more question.

When I load my customized robot using the UI of Robot Navigation, the robot moves well.

If I press stop on Omniverse Isaac and play again, the robot’s move or rotate will not work.
What should I do?

I will attach the video below.

Hi @gudwnzm

Unfortunately, I can’t find enough information in the video to help detect the problem…
Is there any message displayed in the console? Is there a snippet available?

Hi @toni.sm

There is no message from the console.
I will send you the .usd and code to give you more information.

import omni.ext
import omni.ui as ui

from pxr import Gf
import carb
import omni.usd
import omni.ext
import omni.ui as ui
import omni.physx as _physx
from omni.kit.menu.utils import add_menu_items, remove_menu_items, MenuItemDescription
from pxr import UsdGeom
import math
from omni.isaac.ui.ui_utils import (
    setup_ui_headers,
    get_style,
    btn_builder,
    xyz_builder,
    add_separator,
    dropdown_builder,
    combo_floatfield_slider_builder,
)
import omni
import asyncio
import gc
import weakref
import numpy as np
from omni.isaac.dynamic_control import _dynamic_control
from .utils.simple_robot_controller import RobotController
from omni.isaac.core.utils.stage import set_stage_up_axis
from omni.isaac.core.utils.prims import create_prim
from omni.isaac.core import PhysicsContext
from omni.isaac.core.utils.nucleus import find_nucleus_server
from omni.isaac.range_sensor import _range_sensor

EXTENSION_NAME = "AMR Navigation"


def create_xyz(init={"X": 100, "Y": 100, "Z": 0}):
    all_axis = ["X", "Y", "Z"]
    colors = {"X": 0xFF5555AA, "Y": 0xFF76A371, "Z": 0xFFA07D4F}
    float_drags = {}
    for axis in all_axis:
        with ui.HStack():
            with ui.ZStack(width=15):
                ui.Rectangle(
                    width=15,
                    height=20,
                    style={"background_color": colors[axis], "border_radius": 3, "corner_flag": ui.CornerFlag.LEFT},
                )
                ui.Label(axis, name="transform_label", alignment=ui.Alignment.CENTER)
            float_drags[axis] = ui.FloatDrag(name="transform", min=-1000000, max=1000000, step=1, width=100)
            float_drags[axis].model.set_value(init[axis])
    return float_drags


class Extension(omni.ext.IExt):
    def on_startup(self, ext_id: str):
        """Initialize extension and UI elements"""

        self._ext_id = ext_id

        self._timeline = omni.timeline.get_timeline_interface()
        self._viewport = omni.kit.viewport.get_default_viewport_window()
        self._usd_context = omni.usd.get_context()
        self._stage = self._usd_context.get_stage()
        self.lidarInterface = _range_sensor.acquire_lidar_sensor_interface()

        self._window = None
        # self._window = ui.Window(EXTENSION_NAME, width=500, height=175, visible=False)
        # self._window.set_visibility_changed_fn(self._on_window)

        menu_items = [
            MenuItemDescription(name=EXTENSION_NAME, onclick_fn=lambda a=weakref.proxy(self): a._menu_callback())
        ]
        self._menu_items = [MenuItemDescription(name="Demos", sub_menu=menu_items)]
        add_menu_items(self._menu_items, "Isaac Examples")
        self._dc = _dynamic_control.acquire_dynamic_control_interface()
        self._build_ui()

        self._setup_done = False
        self._rc = None

    def _menu_callback(self):
        self._window.visible = not self._window.visible

    def _on_window(self, visible):
        if self._window.visible:
            self._sub_stage_event = self._usd_context.get_stage_event_stream().create_subscription_to_pop(
                self._on_stage_event
            )
        else:
            self._sub_stage_event = None

    def _build_ui(self):
        if not self._window:
            self._window = ui.Window(
                title=EXTENSION_NAME, width=0, height=0, visible=False, dockPreference=ui.DockPreference.LEFT_BOTTOM
            )
            self._window.set_visibility_changed_fn(self._on_window)
            with self._window.frame:
                with ui.VStack(spacing=5, height=0):
                    title = "Mobile Robot Navigation Example"
                    doc_link = (
                        "https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/manual_omni_isaac_demos.html"
                    )

                    overview = "This Example shows how to simulate non-obstacle based navigation in Isaac Sim."
                    overview += "\n\nPick a mobile robot to load into the Scene, and then press PLAY to simulate."
                    overview += "\n\nPress the 'Open in IDE' button to view the source code."

                    setup_ui_headers(self._ext_id, __file__, title, doc_link, overview)

                    frame = ui.CollapsableFrame(
                        title="Command Panel",
                        height=0,
                        collapsed=False,
                        style=get_style(),
                        style_type_name_override="CollapsableFrame",
                        horizontal_scrollbar_policy=ui.ScrollBarPolicy.SCROLLBAR_AS_NEEDED,
                        vertical_scrollbar_policy=ui.ScrollBarPolicy.SCROLLBAR_ALWAYS_ON,
                    )
                    with frame:
                        with ui.VStack(style=get_style(), spacing=5):

                            args = {
                                "label": "Robot Type",
                                "default_val": 0,
                                "tooltip": "Select which type of Robot to load",
                                "items": ["AMR"],
                            }
                            self._robot_option = dropdown_builder(**args)

                            args = {
                                "label": "Load Robot",
                                "type": "button",
                                "text": "Load",
                                "tooltip": "Load a mobile robot into the Scene",
                                "on_clicked_fn": self._on_environment_setup,
                            }
                            self._load_btn = btn_builder(**args)

                            args = {
                                "label": "Move Robot",
                                "type": "button",
                                "text": "Move",
                                "tooltip": "Move the robot Forward",
                                "on_clicked_fn": self._on_move_fn,
                            }
                            self._move_btn = btn_builder(**args)

                            args = {
                                "label": "Spin Robot",
                                "type": "button",
                                "text": "Rotate",
                                "tooltip": "Rotate the robot",
                                "on_clicked_fn": self._on_rotate_fn,
                            }
                            self._rotate_btn = btn_builder(**args)

                            add_separator()

                            args = {
                                "label": "Target Pose",
                                "axis_count": 3,
                                "min": -1000,
                                "max": 1000,
                                "step": 1,
                                "tooltip": "Pose is specified as (X, Y, theta)",
                            }
                            self.goal_coord = xyz_builder(**args)
                            args = {"label": "Speed Coefficient", "default_val": 0.5, "min": 0, "max": 1, "step": 0.05}
                            self._start_vel, _ = combo_floatfield_slider_builder(**args)
                            args = {"label": "Accel Coefficient", "default_val": 0.02, "min": 0, "max": 1, "step": 0.01}
                            self._start_acc, _ = combo_floatfield_slider_builder(**args)
                            args = {"label": "max speed", "default_val": 150.0, "min": 0, "max": 300.0, "step": 1}
                            self._max_speed, _ = combo_floatfield_slider_builder(**args)
                            args = {
                                "label": "Move to Target",
                                "type": "button",
                                "text": "Move",
                                "tooltip": "Move robot to target pose",
                                "on_clicked_fn": self._on_navigate_fn,
                            }
                            self._navigate_btn = btn_builder(**args)

                            args = {
                                "label": "Stop",
                                "type": "button",
                                "text": "Stop",
                                "tooltip": "Pause the robot when navigating",
                                "on_clicked_fn": self._on_navigate_stop_fn,
                            }
                            self._stop_btn = btn_builder(**args)

                            self._stop_btn.enabled = False

                            ui.Spacer()

    async def _create_robot(self, task):
        done, pending = await asyncio.wait({task})
        if task in done:
            print("Loading Robot Enviornment")
            # self._viewport.set_camera_position("/OmniverseKit_Persp", 300, 300, 100, True)
            self._viewport.set_camera_position("/OmniverseKit_Persp", 300, 300, 300, True)
            self._viewport.set_camera_target("/OmniverseKit_Persp", 0, 0, 0, True)
            self._stage = self._usd_context.get_stage()
            result, nucleus_server = find_nucleus_server()
            if result is False:
                carb.log_error("Could not find nucleus server with /Isaac folder")
                return
            self._asset_path = nucleus_server + "/Isaac"
            
            current_robot_index = self._robot_option.get_item_value_model().as_int
            self._robot_prim_path = "/robot"
            if current_robot_index == 0:
                asset_path = nucleus_server + "/Projects" + "/test"
                
                robot_usd = asset_path + "/mk3_third.usd"
                self._robot_chassis = self._robot_prim_path + "/chassis"
                self._robot_wheels = ["left_wheel_joint", "right_wheel_joint"]
                self._robot_wheels_speed = [9, 9]
                self._wheelbase_Length = 0.56
                self._wheel_radius = 0.085

            set_stage_up_axis("z")
            PhysicsContext(physics_dt=1.0 / 60.0)
            create_prim(
                prim_path="/background",
                usd_path=self._asset_path + "/Environments/Grid/gridroom_curved.usd",
                
                # position=np.array([0, 0, -9]),
                position=np.array([-250, -300, -9]),
            )

            # setup high-level robot prim
            self.prim = self._stage.DefinePrim(self._robot_prim_path, "Xform")
            self.prim.GetReferences().AddReference(robot_usd)

    def _on_stage_event(self, event):
        self._stage = self._usd_context.get_stage()
        if event.type == int(omni.usd.StageEventType.OPENED):
            self._move_btn.enabled = self._setup_done
            self._rotate_btn.enabled = self._setup_done
            self._navigate_btn.enabled = self._setup_done
            self._stop_btn.enabled = self._setup_done
            self._stage_unit = UsdGeom.GetStageMetersPerUnit(self._stage)
            if self._rc:
                self._rc.enable_navigation(False)
            self._setup_done = False

    async def _play(self, task):
        done, pending = await asyncio.wait({task})
        if task in done:
            self._timeline.play()
            await asyncio.sleep(1)

    async def _on_setup_fn(self, task):
        done, pending = await asyncio.wait({task})
        if task in done:
            self._stage = self._usd_context.get_stage()
            # setup robot controller
            self._rc = RobotController(
                self._stage,
                # self._timeline,
                self._dc,
                self._robot_prim_path,
                self._robot_chassis,
                self._robot_wheels,
                self._robot_wheels_speed,
                [0.02, 0.05],
                self._wheelbase_Length,
                self._wheel_radius,
            )
            self._rc.control_setup()
            # start stepping
            self._editor_event_subscription = _physx.get_physx_interface().subscribe_physics_step_events(
                self._rc.update
            )
            self._debug_draw_subs = (
                omni.kit.app.get_app().get_update_event_stream().create_subscription_to_pop(self._rc.draw_path)
            )


    async def get_lidar_param(self):
        await omni.kit.app.get_app().next_update_async()
        self.lidarPath = "/robot/chassis/Lidar"
        self._timeline.pause()
        depth = self.lidarInterface.get_linear_depth_data(self.lidarPath)
        zenith = self.lidarInterface.get_zenith_data(self.lidarPath)
        azimuth = self.lidarInterface.get_azimuth_data(self.lidarPath)

        print("depth", depth)
        print("zenith", zenith)
        print("azimuth", azimuth)

    
    def _lidar_print(self):
        self.timeline.play()
        asyncio.ensure_future(self.get_lidar_param())    
    




    def _on_environment_setup(self):
        # wait for new stage before creating robot
        task = asyncio.ensure_future(omni.usd.get_context().new_stage_async())
        task1 = asyncio.ensure_future(self._create_robot(task))
        # set editor to play before setting up robot controller
        task2 = asyncio.ensure_future(self._play(task1))
        asyncio.ensure_future(self._on_setup_fn(task2))

        # self._load_btn.enabled=False
        self._move_btn.enabled = True
        self._rotate_btn.enabled = True
        self._navigate_btn.enabled = True
        self._stop_btn.enabled = True
        self._setup_done = True

    def _on_move_fn(self):
        print("Moving forward")
        self._rc.control_command(9, 9)

    def _on_rotate_fn(self):
        print("Rotating in-place")
        self._rc.control_command(3, -3)

    def _on_navigate_fn(self):
        goal_x = self.goal_coord[0].get_value_as_float() * self._stage_unit
        goal_y = self.goal_coord[1].get_value_as_float() * self._stage_unit
        goal_z = self.goal_coord[2].get_value_as_float()
        max_speed = self._max_speed.get_value_as_float() * self._stage_unit
        print("Navigating to goal ({}, {}, {})".format(goal_x, goal_y, goal_z))
        sv = self._start_vel.get_value_as_float()
        sa = self._start_acc.get_value_as_float()

        gv = sv  # self._goal_speed.get_value_as_float()
        ga = sa  # self._goal_acc.get_value_as_float()
        self._rc.set_goal(goal_x, goal_y, math.radians(goal_z), sv, sa, gv, ga, max_speed)
        self._rc.enable_navigation(True)

    def _on_navigate_stop_fn(self):
        print("Navigation Stopped")
        self._rc.enable_navigation(False)
        self._rc.control_command(0, 0)

    def on_shutdown(self):
        self._rc = None
        self._timeline.stop()
        self._editor_event_subscription = None
        remove_menu_items(self._menu_items, "Isaac Examples")
        self._window = None
        gc.collect()

Hi @gudwnzm
It seems that something is happening with the articulation handler when the simulation is stopped using the button. A deeper analysis of the code would be necessary to identify the problem…

In the meantime, updating the articulation and joints with the self._rc.control_setup() method in each of the motion control functions solves the problem.

    def _on_move_fn(self):
        self._rc.control_setup()
        self._rc.control_command(9, 9)

    def _on_rotate_fn(self):
        print("Rotating in-place")
        self._rc.control_setup()
        self._rc.control_command(3, -3)

    def _on_navigate_fn(self):
        self._rc.control_setup()
        ...
1 Like

Hi @toni.sm

As you said, I need a deeper analysis of the code.

But thanks to you, the problem was solved well.
Regardless of this subject, I would like to ask one question.

Currently, I am using Omniverse Isaac sim’s Navigation Sample Applications modified.
As you know, in Navigation Sample Applications, robots are reaching their destinations using the Quintic Polynomials Planner.
Quintic Polynomials Planner

I want to use A-star when robots go to their destination. Is there a good example or a way to change the Quintic Polynomials Planner to A-star?

Hi @gudwnzm

You can do whatever you want just by programming :)

To implement A* you will need some kind of map on which to apply the path search algorithm and a control that allows you to follow the identified trajectory…

Isaac Sim’s Navigation Sample Application demonstrates goal-driven navigation in an environment with no obstacles.

At that point, if you want to implement more and more features, maybe it is time to go for more advanced navigation frameworks/stacks, such as the ROS Navigation, that allows you to do dynamic path planning, obstacle avoidance, etc.

Hi @toni.sm

Thank you for your advice.
I will refer to your advice.

While I was working on Isaac sim, this error kept coming up, so I can’t proceed with tutorial.
How do we solve this?

2022-06-20 06:50:55 [Error] [omni.ext.impl._internal] Failed to import python module omni.isaac.examples.tests. Error: cannot import name ‘get_assets_root_path’ from ‘omni.isaac.core.utils.nucleus’ (/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.core/omni/isaac/core/utils/nucleus.py). Traceback:
Traceback (most recent call last):
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/kit/plugins/bindings-python/omni/ext/impl/_internal.py”, line 65, in import_module
return importlib.import_module(name)
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/kit/python/lib/python3.7/importlib/init.py”, line 127, in import_module
return _bootstrap._gcd_import(name[level:], package, level)
File “”, line 1006, in _gcd_import
File “”, line 983, in _find_and_load
File “”, line 967, in _find_and_load_unlocked
File “”, line 677, in _load_unlocked
File “”, line 728, in exec_module
File “”, line 219, in _call_with_frames_removed
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.examples/omni/isaac/examples/tests/init.py”, line 17, in
from .test_hello_world import *
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.examples/omni/isaac/examples/tests/test_hello_world.py”, line 18, in
from omni.isaac.examples.hello_world import HelloWorld
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.examples/omni/isaac/examples/hello_world/init.py”, line 10, in
from omni.isaac.examples.hello_world.hello_world import HelloWorld
File “/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.examples/omni/isaac/examples/hello_world/hello_world.py”, line 3, in
from omni.isaac.core.utils.nucleus import get_assets_root_path
ImportError: cannot import name ‘get_assets_root_path’ from ‘omni.isaac.core.utils.nucleus’ (/home/tommy/.local/share/ov/pkg/isaac_sim-2021.2.1/exts/omni.isaac.core/omni/isaac/core/utils/nucleus.py)

Hi @toni.sm

I thought the error shown above was a version problem, so I updated it to the latest version from Isaac Sim 2021.2.1 to Isaac Sim 2022.1.0.
After updating to the latest version, there is no same error above, but there is a strange problem with the existing Robot Navigation.
I brought my customized robot to a customized environment with Rigid body and collider. Unlike before, gravity and physics are not applied.
I will attach the video below.

Hi @gudwnzm

Mmmm, maybe it is related to the stage units…
The new version uses meters as default instead of centimeters

There is a tool for changing the stage unit (USD Unit Converter) under Isaac Utils menu

Hi @toni.sm

I’m sorry I kept asking you questions on this topic even though the topic here has been resolved.

I want to ask you one last question.
I want to copy the Omniverse example, Adding Multiple Robots, and apply it to my robot.
But I keep causing the same error.
Compared to the example robot, jetbot.usd," and my robot, the joint is not much different.
If I look at the error, I don’t think I can get the joint_position.
The code takes the robot’s position value and puts it in the goal_position, but this part seems to be a problem.

The error contents and code are as follows.

from omni.isaac.examples.base_sample import BaseSample
from omni.isaac.core.utils.nucleus import get_assets_root_path
from omni.isaac.wheeled_robots.robots import WheeledRobot
from omni.isaac.core.utils.types import ArticulationAction
from omni.isaac.core.controllers import BaseController
from omni.isaac.motion_generation import WheelBasePoseController
from omni.isaac.wheeled_robots.controllers.differential_controller import DifferentialController
import numpy as np

class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        world.scene.add_default_ground_plane()
        assets_root_path = get_assets_root_path()
        # jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        jetbot_asset_path = "omniverse://localhost/Projects/test/mk3_third.usd"
        world.scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Robot",
                name="fancy_robot",
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],
                create_robot=True,
                usd_path=jetbot_asset_path,
            )
        )
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        self._jetbot = self._world.scene.get_object("fancy_robot")
        self._world.add_physics_callback("sending_actions", callback_fn=self.send_robot_actions)
        # Initialize our controller after load and the first reset
        self._my_controller = WheelBasePoseController(name="cool_controller",
                                                        open_loop_wheel_controller=
                                                            DifferentialController(name="simple_control",
                                                                                    wheel_radius=0.03, wheel_base=0.1125),
                                                    is_holonomic=False)
        return
    
    def send_robot_actions(self, step_size):
        position, orientation = self._jetbot.get_world_pose()
        self._jetbot.apply_action(self._my_controller.forward(start_position=position,
                                                            start_orientation=orientation,
                                                            goal_position=np.array([0.8, 0.8])))
        
        
        print("AMR position is : " + str(position))
        print("AMR's orientation is : " + str(orientation))
        
        return

Hi @toni.sm

I haven’t solved the problem yet.
Even though the left_wheel_joint and right_wheel_joint of Jetbot and my robot are the same, the problem still occurs.

First of all, what I want to do with my robot is to put up several robots and arrive at the destination without algorithms.
So I’m starting by customizing it by referring to an example of Adding Multiple Robots.
Help me.

https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_core_adding_multiple_robots.html

Hi @gudwnzm

Make sure that the joints of your robot have the angular drive property established.
By the way, don’t forget to update the wheel_radius and wheel_base values for your model :)

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.