Note: For any Isaac Lab topics, please submit your topic to its GitHub repo (GitHub - isaac-sim/IsaacLab: Unified framework for robot learning built on NVIDIA Isaac Sim) following the instructions provided on Isaac Lab’s Contributing Guidelines (Contribution Guidelines — Isaac Lab Documentation).
Please provide all relevant details below before submitting your post. This will help the community provide more accurate and timely assistance. After submitting, you can check the appropriate boxes. Remember, you can always edit your post later to include additional information if needed.
Isaac Sim Version
4.5.0
4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):
Operating System
Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):
GPU Information
- Model: RTX 4060
- Driver Version: 535.183.01
Topic Description
Detailed Description
Expected result
Overcome gravity
Actual result
Can’t overcome gravity, keep going down
Steps to Reproduce
- Make simple 1-dof robot using revolute joint (1-link robot)
- Set articulation control mode to “effort” using “switch_dof_control_mode” API
- Get the generalized gravity force using “get_generalized_gravity_forces” API
- Get the Coriolis and centrifugal force using “get_coriolis_and_centrifugal_forces” API
- After adding the two values, it was set in joint_efforts. Using “ArticulationAction” API
- Apply action using “apply_action” API
3-6 is repeated every physics step.
Hi @jinkk.kim,
Thank you for posting your question. I will look at this promptly and try to reproduce the issue.
@michalin Is there any progress?
I want to resolve this issue…
Hi @jinkk.kim,
So sorry for taking so long to get back to you. I have tried to reproduce the gravity compensation on my own setup and it seems to work for me. What I observe in my setup:
- When there is a bit of joint damping, joint will stop wherever I drag it to with no effect from gravity pulling it down.
- When no damping is present it will spin at a constant speed.
Here is the script I use:
#!/usr/bin/env python3
# Copyright (c) 2022-2024, 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.
"""
This script demonstrates a single DOF link with gravity compensation.
It creates a simple articulation with one revolute joint and applies
gravity compensation to maintain the link's position.
"""
from isaacsim import SimulationApp
# Create simulation app (not headless so we can see the link)
simulation_app = SimulationApp({"headless": False})
import numpy as np
from isaacsim.core.api import World
from isaacsim.core.prims import Articulation
from isaacsim.core.utils.articulations import add_articulation_root
from pxr import UsdGeom, UsdPhysics, Gf
# Create world with default CPU backend
my_world = World(stage_units_in_meters=1.0)
print("Using numpy backend")
# Add default ground plane
my_world.scene.add_default_ground_plane()
# Get stage
stage = simulation_app.context.get_stage()
# Create a Xform for the SingleDOFArm
arm_path = "/World/SingleDOFArm"
arm_xform = UsdGeom.Xform.Define(stage, arm_path)
# Add articulation root to the xform prim
add_articulation_root(arm_xform.GetPrim())
# Create base link
base_path = "/World/SingleDOFArm/base"
base = UsdGeom.Cube.Define(stage, base_path)
base.CreateSizeAttr(0.2)
base.AddTranslateOp().Set(Gf.Vec3f(0, 0, 0.5))
base_prim = base.GetPrim()
# Apply physics to base
UsdPhysics.CollisionAPI.Apply(base_prim)
rigid_api = UsdPhysics.RigidBodyAPI.Apply(base_prim)
mass_api = UsdPhysics.MassAPI.Apply(base_prim)
mass_api.CreateMassAttr().Set(1.0) # Set mass to 1 kg
# Create moving link
link_path = "/World/SingleDOFArm/link"
link = UsdGeom.Cylinder.Define(stage, link_path)
link.CreateRadiusAttr(0.05)
link.CreateHeightAttr(0.5)
link.AddTranslateOp().Set(Gf.Vec3f(0, 0, 0.85))
link_prim = link.GetPrim()
# Apply physics to link
UsdPhysics.CollisionAPI.Apply(link_prim)
rigid_api = UsdPhysics.RigidBodyAPI.Apply(link_prim)
mass_api = UsdPhysics.MassAPI.Apply(link_prim)
mass_api.CreateMassAttr().Set(0.5) # Set mass to 0.5 kg
# Fix the base to the world using a fixed joint
fixed_joint_path = "/World/SingleDOFArm/FixedJoint"
fixed_joint = UsdPhysics.FixedJoint.Define(stage, fixed_joint_path)
fixed_joint.CreateBody0Rel().AddTarget("/World")
fixed_joint.CreateBody1Rel().AddTarget(base_path)
# Create a revolute joint between the base and the link
joint_path = "/World/SingleDOFArm/RevoluteJoint"
revolute_joint = UsdPhysics.RevoluteJoint.Define(stage, joint_path)
revolute_joint.CreateBody0Rel().AddTarget(base_path)
revolute_joint.CreateBody1Rel().AddTarget(link_path)
# Set the joint's local position
local_pos0 = Gf.Vec3f(0, 0, 0.1) # Top of base
local_pos1 = Gf.Vec3f(0, 0, -0.25) # Bottom of link
revolute_joint.CreateLocalPos0Attr().Set(local_pos0)
revolute_joint.CreateLocalPos1Attr().Set(local_pos1)
# Set the joint axis to rotate around the X-axis
revolute_joint.CreateAxisAttr().Set("X")
# Apply joint drive with damping using the DriveAPI
drive_api = UsdPhysics.DriveAPI.Apply(revolute_joint.GetPrim(), "angular")
drive_api.CreateDampingAttr().Set(0.001) # Set damping coefficient
drive_api.CreateStiffnessAttr().Set(0.0) # No stiffness for free rotation
drive_api.CreateMaxForceAttr().Set(5000.0) # Set maximum force the joint can apply
# Create the articulation for the arm
arm = Articulation(prim_paths_expr="/World/SingleDOFArm", name="single_dof_arm")
my_world.scene.add(arm)
# Reset world to initialize scene
my_world.reset()
# Prepare data for joint positions using numpy
zero_position = np.array([np.pi/2])
joint_indices = np.array([0], dtype=np.int32)
# Set initial position
arm.set_joint_positions(zero_position)
# Keep simulation running
print("Simulation started. Press Ctrl+C to exit.")
try:
while simulation_app.is_running():
# Get gravity and coriolis forces
grav_efforts = arm.get_generalized_gravity_forces(joint_indices=joint_indices)
coriolis_centrifugal_efforts = arm.get_coriolis_and_centrifugal_forces(joint_indices=joint_indices)
# Apply gravity compensation torque
arm.set_joint_efforts(efforts=grav_efforts + coriolis_centrifugal_efforts, joint_indices=joint_indices)
my_world.step(render=True)
except KeyboardInterrupt:
print("Simulation stopped by user")
finally:
# Cleanup
simulation_app.close()
I hope this helps.
Michael
@michalin
Thank you for the example code.
I have some additional questions.
Q1.
For comparison, the joint damping value was set to 0. However, it does not spin.
Is it right to set like this?
drive_api.CreateDampingAttr(). Set (0.0)
Q2.
Does your opinion mean that a joint damping value is required for effort control?
If you look at the description of the apply_action function in the articulation.py file, it is specified as follows.
High stiffness makes the joints snap faster and harder to the desired target,
and higher damping smoothes but also slows down the joint's movement to target
* For position control, set relatively high stiffness and low damping (to reduce vibrations)
* For velocity control, stiffness must be set to zero with a non-zero damping
* For effort control, stiffness and damping must be set to zero
path of aticulation.py
isaacsim/exts/isaacsim.core.prims/isaacsim/core/prims/impl/articulation.py
Q3.
If joint damping is required during effort control, should the damping be adjusted according to the mass of the link?
Is there a way to adjust the damping value well?
Q4.
I want to test with ur16e. How should I modify the example code above?
@michalin
I wrote the contents of Q4. above in script, but it doesn’t work properly.
How can I solve it?
#!/usr/bin/env python3
# Copyright (c) 2022-2024, 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.
"""
This script demonstrates a single DOF link with gravity compensation.
It creates a simple articulation with one revolute joint and applies
gravity compensation to maintain the link's position.
"""
from isaacsim import SimulationApp
# Create simulation app (not headless so we can see the link)
simulation_app = SimulationApp({"headless": False})
from isaacsim.storage.native import get_assets_root_path
import numpy as np
from isaacsim.core.api import World
from isaacsim.core.prims import Articulation, XFormPrim
from isaacsim.core.utils.articulations import add_articulation_root
from pxr import UsdGeom, UsdPhysics, Gf, UsdLux, Sdf
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.core.utils.stage import get_current_stage
assets_root_path = get_assets_root_path()
if assets_root_path is None:
carb.log_error("Could not find Isaac Sim assets folder")
simulation_app.close()
sys.exit()
# Create world with default CPU backend
my_world = World(stage_units_in_meters=1.0)
print("Using numpy backend")
# Add default ground plane
# ! not use ground
# my_world.scene.add_default_ground_plane()
# Get stage
stage = simulation_app.context.get_stage()
# Set Light
sphereLight = UsdLux.SphereLight.Define(
get_current_stage(), Sdf.Path("/World/SphereLight")
)
sphereLight.CreateRadiusAttr(2)
sphereLight.CreateIntensityAttr(100000)
XFormPrim(str(sphereLight.GetPath())).set_world_poses(np.array([[6.5, 0, 12]]))
asset_path = assets_root_path + "/Isaac/Robots/UniversalRobots/ur16e/ur16e.usd"
add_reference_to_stage(usd_path=asset_path, prim_path="/World/UR16e")
# Create the articulation for the arm
arm = Articulation(prim_paths_expr="/World/UR16e", name="test_robot")
my_world.scene.add(arm)
# Reset world to initialize scene
my_world.reset()
# Prepare data for joint positions using numpy
zero_position = np.array([0, 90, -140, -40, 90, 0])
zero_position = np.deg2rad(zero_position)
joint_name_list = [
"shoulder_pan_joint",
"shoulder_lift_joint",
"elbow_joint",
"wrist_1_joint",
"wrist_2_joint",
"wrist_3_joint",
]
joint_idx_list = list()
for idx, data in enumerate(joint_name_list):
joint_idx = arm.get_joint_index(joint_name=data)
joint_idx_list.append(joint_idx)
# for checking idx
print(f"joint_idx_list: {joint_idx_list}")
# Set initial position
arm.set_joint_positions(positions=zero_position, joint_names=joint_name_list)
# switch control mode. stiffness, damping set 0
arm.switch_control_mode(mode="effort", joint_names=joint_name_list)
# set damping 0.001
data = np.zeros(len(joint_name_list)) + 0.001
print(f"data: {data}")
arm.set_gains(kds=data, joint_names=joint_name_list)
# for checking gains
stiffness, damping = arm.get_gains()
print(f"stiffness: {stiffness}")
print(f"damping: {damping}")
# Keep simulation running
print("Simulation started. Press Ctrl+C to exit.")
try:
while simulation_app.is_running():
# Get gravity and coriolis forces
grav_efforts = arm.get_generalized_gravity_forces(joint_indices=joint_idx_list)
coriolis_centrifugal_efforts = arm.get_coriolis_and_centrifugal_forces(
joint_indices=joint_idx_list
)
# Apply gravity compensation torque
arm.set_joint_efforts(
efforts=grav_efforts + coriolis_centrifugal_efforts,
joint_indices=joint_idx_list,
)
my_world.step(render=True)
except KeyboardInterrupt:
print("Simulation stopped by user")
finally:
# Cleanup
simulation_app.close()
Could you check my issues?
Looking into this promptly