How to simulate a robot arm in Isaac Sim without physics (no gravity or inertia)?

Content:

I’m planning to implement a robot arm simulation in Isaac Sim, but I want to do it without using the physics engine.

Currently, in order to construct the robot arm, I need to connect each link using joints, which requires adding a RigidBody component. However, once the simulation starts, the robot arm falls due to gravity, which I want to avoid.

What I want is a robot arm that moves precisely to target positions and stops exactly without the effects of gravity, inertia, or any other physical behavior. In other words, I want a purely kinematic simulation without dynamic physics.

Is there a way to achieve this in Isaac Sim?

Isaac Sim Version

4.5.0

Operating System

Windows 10

GPU Information

  • Model: RXT 2070
  • Driver Version:

Topic Description

Detailed Description

(Describe the issue in detail, including what you were trying to do, what you expected to happen, and what actually happened)


2025-04-03 10-32-09

Even after disabling gravity, there is still some oscillation when moving to the target position. How can I make the robot arm stop exactly at the target without any shaking? I want to achieve this without inertia or using the physics engine.

For most of the joints, I’ve set damping to 0. However, setting stiffness to 0 prevents any movement, so I had to assign it a non-zero value to make the joints respond.

@skwix7905 i have not done anything with zero G, so i’ll defer to the mods to address your question. i did, however, saw this post from a while back that may/may not be relevant to what you are after.

1 Like

Hi @skwix7905,

Thanks for your question. If you use the Articulation set_joint_positions you can force the robot to any joint position you want. Simulation will still run to determine the torque that is required to get the robot to move to those trajectories, but the motion won’t be affected by gravity or anything else but the position you are setting.

Here is a simple script to do this

# SPDX-FileCopyrightText: Copyright (c) 2021-2025 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
# SPDX-License-Identifier: LicenseRef-NvidiaProprietary
#
# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
# property and proprietary rights in and to this material, related
# documentation and any modifications thereto. Any use, reproduction,
# disclosure or distribution of this material and related documentation
# without an express license agreement from NVIDIA CORPORATION or
# its affiliates is strictly prohibited.

import numpy as np
from isaacsim import SimulationApp

# Create a simulation app instance
simulation_app = SimulationApp({"headless": False})

from isaacsim.core.api import World
from isaacsim.core.api.tasks import BaseTask
from isaacsim.core.utils.types import ArticulationAction
from isaacsim.robot.manipulators.examples.franka import Franka

# Create a world
my_world = World(stage_units_in_meters=1.0)

# Add default ground plane
my_world.scene.add_default_ground_plane()

# Add the Franka robot to the scene
franka = my_world.scene.add(
    Franka(
        prim_path="/World/Franka",
        name="franka",
        gripper_dof_names=["panda_finger_joint1", "panda_finger_joint2"],
        end_effector_prim_name="panda_rightfinger",
        gripper_open_position=np.array([0.4, 0.4]) / 0.01,
        gripper_closed_position=np.array([0.0, 0.0]),
    )
)

# Reset world to initialize scene
my_world.reset()

# Define target joint positions
target_positions = np.array([0.0, 0.3, 0.0, -1.5, 0.0, 1.8, 0.0, 0.0, 0.0])
joint_indices = np.arange(9, dtype=np.int32)

print("Simulation started. Setting Franka to target position.")
print("Press Ctrl+C to exit.")
# Define sinusoidal trajectory parameters
amplitude = np.array([0.3, 0.3, 0.3, 0.3, 0.3, 0.3, 0.3, 0.1, 0.1])  # Amplitude for each joint
frequency = np.array([4.5, 0, 0, 0, 0, 0, 0, 0, 0])  # Frequency for each joint
phase = np.array([0.0, 0.5, 1.0, 1.5, 2.0, 2.5, 3.0, 0.0, np.pi])    # Phase offset for each joint
center_position = np.array([0.0, 0.3, 0.0, -1.5, 0.0, 1.8, 0.0, 0.2, 0.2])  # Center position for oscillation

# Time counter for simulation
sim_time = 0.0
time_step = 1.0 / 60.0  # Assuming 60 Hz simulation

# Main simulation loop
while simulation_app.is_running():
    # Calculate joint positions based on sinusoidal trajectory
    joint_positions = center_position + amplitude * np.sin(2 * np.pi * frequency * sim_time + phase)
    
    # Set joint positions
    franka.set_joint_positions(joint_positions, joint_indices=joint_indices)
    
    # Step the simulation
    my_world.step(render=True)
    
    # Update simulation time
    sim_time += time_step

# Cleanup
simulation_app.close()