Replies: 6 comments
-
Can you post your robot config? Are you spawning from a urdf or usd? And how have you configured the joint drives, articulation props, etc.? I have also seen some weird behavior from the newer urdf importer but can try to advise if you share the config. |
Beta Was this translation helpful? Give feedback.
-
@KyleM73 I spawn from a USD, but it's converted from a URDF. My config can be seen below, along with the rest of my code, which I provide in case I'm performing something incorrectly, but I configure the joint, articulation, and rigid body properties through the standard approach for other robots, as seen in the shown assets. I also do a sanity check and set the values using the provided isaaclab functions, directly setting them in physx at the first environment step. The plot data uses the "head_pan" joint for the real world and the simulation. I did end up getting the implicit actuator to work "good enough". For whatever reason, if I set the render interval to 1, making it equal to the number of sim physics steps, it no longer has these instant jumps to the goal position (this makes me think the control loop is tied to framerate). I would still like to get the actuator models in Isaac lab working as they work well for me on other robots. Thanks for the reply! # Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
""" Used to for PD tuning of articulations.
.. code-block:: bash
# Usage
./isaaclab.sh -p scripts/tutorials/01_assets/run_articulation.py
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from typing import TYPE_CHECKING
import math
from isaaclab.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="Tutorial on spawning and interacting with an articulation.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import torch
import numpy as np
import isaacsim.core.utils.prims as prim_utils
from typing import TYPE_CHECKING, Literal
import carb
import isaacsim.core.utils.stage as stage_utils
import omni.log
import omni.physics.tensors.impl.api as physx
from pxr import PhysxSchema, UsdPhysics
import isaaclab.sim as sim_utils
import isaaclab.utils.math as math_utils
import isaaclab.utils.string as string_utils
from isaaclab.actuators import ActuatorBase, ActuatorBaseCfg, ImplicitActuator, ImplicitActuatorCfg, IdealPDActuator, IdealPDActuatorCfg, DCMotor, DCMotorCfg, ActuatorNetMLPCfg
from isaaclab.assets import Articulation, ArticulationCfg, RigidObject, RigidObjectCfg
from isaaclab.managers import SceneEntityCfg
from isaaclab.sim import SimulationContext
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR
from isaaclab.assets.asset_base import AssetBase
from isaaclab.assets.articulation.articulation_data import ArticulationData
import isaacsim.core.utils.prims as prim_utils
import isaaclab.sim as sim_utils
from isaaclab.assets import Articulation
if TYPE_CHECKING:
from isaaclab.assets.articulation.articulation_cfg import ArticulationCfg
##
# Pre-defined configs
##
def design_scene() -> tuple[dict, list[list[float]]]:
"""Designs the scene."""
# create the scene
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
cfg = sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
origins = [[0.0, 0.0, 0.0]]
# Setup for ActuatorNetMLP (not using)
OP3_ACTUATOR_CFG = ActuatorNetMLPCfg(
joint_names_expr=[".*hip.*", ".*knee.*", ".*ank.*", ".*_sho_pitch", ".*_sho_roll", ".*_el", "head_pan", "head_tilt"],
network_file=f"C:/Users/VR2/Documents/op3_effort_actuator_net_v3.pt",
pos_scale=-1.0,
vel_scale=1.0,
torque_scale=1.0,
input_order="pos_vel",
input_idx=[0, 1, 2],
effort_limit=0.8,
velocity_limit=5,
saturation_effort=0.8,
is_position=True, # True for position control, False for torque control
)
robot_cfg = ArticulationCfg(
prim_path="/World/envs/env_.*/Robot",
spawn=sim_utils.UsdFileCfg(
usd_path="C:/Users/VR2/Desktop/IsaacLab_Robots/op3_IsaacLab/op3_description/urdf/op3/op3.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False,
solver_position_iteration_count=4,
solver_velocity_iteration_count=4,
fix_root_link=True,
),
copy_from_source=False,
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.25),
joint_pos={
"l_hip_yaw": 0.0,
"l_hip_roll": -0.04,
"l_hip_pitch": -0.65,
"l_knee": 1.38,
"l_ank_pitch": 0.83,
"l_ank_roll": -0.01,
"r_hip_yaw": 0.0,
"r_hip_roll": 0.04,
"r_hip_pitch": 0.65,
"r_knee": -1.38,
"r_ank_pitch": -0.83,
"r_ank_roll": 0.01,
"l_sho_pitch" : 0.0,
"l_sho_roll" : 0.0,
"l_el" : 0.0,
"r_sho_pitch" : 0.0,
"r_sho_roll" : 0.0,
"r_el" : 0.0,
"head_pan" : 0.0,
"head_tilt" : 0.0,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.85,
actuators={
"legs": ImplicitActuatorCfg(
joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee.*"],
armature=0.045,
friction=0.03,
effort_limit=5,
effort_limit_sim=5,
velocity_limit=5,
velocity_limit_sim=5,
stiffness={
".*_hip_yaw": 45.0,
".*_hip_roll": 45.0,
".*_hip_pitch": 45.0,
".*_knee": 45.0,
},
damping={
".*_hip_yaw": 1.5,
".*_hip_roll": 1.5,
".*_hip_pitch": 1.5,
".*_knee": 1.5,
}
),
"feet": IdealPDActuatorCfg(
joint_names_expr=[".*_ank_pitch", ".*_ank_roll"],
armature=0.045,
friction=0.03,
effort_limit=5,
effort_limit_sim=5,
velocity_limit=5,
velocity_limit_sim=5,
stiffness={
".*_ank_pitch": 45.0,
".*_ank_roll": 45.0,
},
damping={
".*_ank_pitch": 1.5,
".*_ank_roll": 1.5,
}
),
"arms": IdealPDActuatorCfg(
joint_names_expr=[".*_sho_pitch", ".*_sho_roll", ".*_el"],
armature=0.045,
friction=0.03,
effort_limit=5,
effort_limit_sim=5,
velocity_limit=5,
velocity_limit_sim=5,
stiffness={
".*_sho_pitch": 45.0,
".*_sho_roll": 45.0,
".*_el": 45.0,
},
damping={
".*_sho_pitch": 1.5,
".*_sho_roll": 1.5,
".*_el": 1.5,
}
),
"head": ImplicitActuatorCfg(
joint_names_expr=["head_pan", "head_tilt"],
armature=0.045,
friction=0.03,
effort_limit=5,
effort_limit_sim=5,
velocity_limit=5,
velocity_limit_sim=5,
stiffness={
"head_pan": 45.0,
"head_tilt": 45.0,
},
damping={
"head_pan": 1.5,
"head_tilt": 1.5,
}
),
},
)
robot = Articulation(cfg=robot_cfg)
# return the scene information
scene_entities = {"robot": robot}
return scene_entities, origins
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor):
"""Runs the simulation loop."""
# Simulation setup
robot = entities["robot"]
sim_dt = sim.get_physics_dt()
print(f"[INFO]: Simulation dt: {sim_dt}")
print(f"[INFO]: Joint ordering: {robot.data.joint_names}")
count = 0
# Data buffers
data = [] # Step response actual position data logging for sim
cmd = [] # Step response goal position data logging for sim
tau_target = [] # Step response requested torque data logging for sim
tau_target2 = [] # Chirp response requested torque data logging for sim
data2 = [] # Chirp response actual position data logging for sim
cmd2 = [] # Chirp response goal position data logging for sim
print(f"[INFO]: Robot data: {robot.data}")
# Step response
while simulation_app.is_running() and count < 800:
# Reset
if count < 1:
print("[INFO]: Resetting robot state...")
# Writing initial pose to sim
root_state = robot.data.default_root_state.clone()
root_state[:, :3] += origins
robot.write_root_pose_to_sim(root_state[:, :7])
robot.write_root_velocity_to_sim(root_state[:, 7:])
# Initial joint state
robot.data.joint_pos_limits[:, 0, 0] = -2*3.14
robot.data.joint_pos_limits[:, 0, 1] = 2*3.14
def_damp = robot.data.default_joint_damping.clone()
def_stiff = robot.data.default_joint_stiffness.clone()
joint_pos = torch.zeros_like(robot.data.default_joint_pos.clone())
joint_vel = torch.zeros_like(robot.data.default_joint_vel.clone())
# Physx type stuffs
com_pos = robot.root_physx_view.get_coms().clone()
masses = robot.data.default_mass.clone()
inertias = robot.data.default_inertia.clone()
indices = torch.tensor(range(len(origins)), dtype=torch.int)
# Set default values to sim
robot.write_joint_armature_to_sim(robot.data.default_joint_armature.clone())
robot.write_joint_friction_to_sim(robot.data.default_joint_friction.clone())
robot.write_joint_effort_limit_to_sim(robot.data.joint_effort_limits.clone())
robot.write_joint_velocity_limit_to_sim(robot.data.joint_velocity_limits.clone())
robot.write_joint_position_limit_to_sim(robot.data.joint_pos_limits.clone())
robot.write_joint_damping_to_sim(def_damp)
robot.write_joint_stiffness_to_sim(def_stiff)
robot.write_joint_state_to_sim(joint_pos, joint_vel)
robot.write_joint_position_limit_to_sim(robot.data.joint_pos_limits.clone())
# Direct write to physx
robot.root_physx_view.set_inertias(inertias.clone(), indices.clone())
robot.root_physx_view.set_masses(masses.clone(), indices.clone())
robot.root_physx_view.set_coms(com_pos.clone(), indices.clone())
robot.root_physx_view.set_dof_limits(robot.data.joint_pos_limits.clone(), indices.clone())
# clear internal buffers
robot.update(sim_dt)
robot.reset()
# sanity check
print(f"[INFO]: default inertia: {robot.data.default_inertia}")
print(f"[INFO]: default mass: {robot.data.default_mass}")
print(f"[INFO]: default com: {robot.root_physx_view.get_coms()}")
print(f"[INFO]: Default joint damping: {def_damp}")
print(f"[INFO]: Default joint stiffness: {def_stiff}")
print(f"[INFO]: Default joint pos: {robot.data.default_joint_pos.clone()}")
print(f"[INFO]: Default joint vel: {robot.data.default_joint_vel.clone()}")
# Logging torque output from actuator model
tau_target.append(robot._data.computed_torque[:, 0].clone())
# Set step response as goal pos after 1 second
if count >= 200:
#sin = 0
sin = np.pi / 4
new_pos = robot.data.default_joint_pos.clone()
new_pos[0, 0] = sin
else:
new_pos = robot.data.default_joint_pos.clone()
# Set goal position
robot.set_joint_position_target(target=new_pos.clone())
# Log data
cmd.append(new_pos[:, 0].clone().numpy())
data.append(robot.data.joint_pos[:, 0].clone().numpy())
# Log data to screen
if count % 10 == 0:
print(f"command pos: {new_pos[:, 0].clone()[0]}, actual pos: {data[-1]}")
# Write dat robo data to sim
robot.write_data_to_sim()
# Perform step
sim.step()
# Increment counter
count += 1
# Update buffers
robot.update(sim_dt)
robot.reset()
##
# ----------- Chirp response -------------------
##
# Chirp parameters -- thank you Mr. GPT
F_START = 0.5 # start frequency (Hz)
F_END = 2.8 # end frequency (Hz)
TEST_DURATION = 4.0 # total time (s)
n_iters = int(200 * TEST_DURATION)
STEP_RAD = math.radians(20)
# Precompute chirp target array
t_array = np.linspace(0, TEST_DURATION, n_iters)
k = (F_END - F_START) / TEST_DURATION
phase_array = 2 * np.pi * (F_START * t_array + 0.5 * k * t_array**2)
target_array = 0 + STEP_RAD * np.sin(phase_array)
# Reset counter
count = 0
# Frequency response
while simulation_app.is_running() and count < 800:
# Reset
if count < 1:
print("[INFO]: Resetting robot state for frequency test...")
# Writing initial pose to sim
root_state = robot.data.default_root_state.clone()
root_state[:, :3] += origins
robot.write_root_pose_to_sim(root_state[:, :7])
robot.write_root_velocity_to_sim(root_state[:, 7:])
# Initial joint state
robot.data.joint_pos_limits[:, 0, 0] = -2*3.14 # if you use the full float of pi it gets angry
robot.data.joint_pos_limits[:, 0, 1] = 2*3.14
def_damp = robot.data.default_joint_damping.clone()
def_stiff = robot.data.default_joint_stiffness.clone()
joint_pos = torch.zeros_like(robot.data.default_joint_pos.clone())
joint_vel = torch.zeros_like(robot.data.default_joint_vel.clone())
# Physx type stuffs
com_pos = robot.root_physx_view.get_coms().clone()
masses = robot.data.default_mass.clone()
inertias = robot.data.default_inertia.clone()
indices = torch.tensor(range(len(origins)), dtype=torch.int)
# Set default values to sim
robot.write_joint_armature_to_sim(robot.data.default_joint_armature.clone())
robot.write_joint_friction_to_sim(robot.data.default_joint_friction.clone())
robot.write_joint_effort_limit_to_sim(robot.data.joint_effort_limits.clone())
robot.write_joint_velocity_limit_to_sim(robot.data.joint_velocity_limits.clone())
robot.write_joint_position_limit_to_sim(robot.data.joint_pos_limits.clone())
robot.write_joint_damping_to_sim(def_damp)
robot.write_joint_stiffness_to_sim(def_stiff)
robot.write_joint_state_to_sim(joint_pos, joint_vel)
robot.write_joint_position_limit_to_sim(robot.data.joint_pos_limits.clone())
# Direct write to physx
robot.root_physx_view.set_inertias(inertias.clone(), indices.clone())
robot.root_physx_view.set_masses(masses.clone(), indices.clone())
robot.root_physx_view.set_coms(com_pos.clone(), indices.clone())
robot.root_physx_view.set_dof_limits(robot.data.joint_pos_limits.clone(), indices.clone())
# clear internal buffers
robot.update(sim_dt)
robot.reset()
# sanity check
print(f"[INFO]: default inertia: {robot.data.default_inertia}")
print(f"[INFO]: default mass: {robot.data.default_mass}")
print(f"[INFO]: default com: {robot.root_physx_view.get_coms()}")
print(f"[INFO]: Default joint damping: {def_damp}")
print(f"[INFO]: Default joint stiffness: {def_stiff}")
print(f"[INFO]: Default joint pos: {robot.data.default_joint_pos.clone()}")
print(f"[INFO]: Default joint vel: {robot.data.default_joint_vel.clone()}")
# Goal position for chirp response
sin = target_array[count]
new_pos = robot.data.default_joint_pos.clone()
new_pos[:, 0] = new_pos[:, 0].clone() + sin
# Set goal position
robot.set_joint_position_target(target=new_pos.clone().to("cpu"))
# Log data
tau_target2.append(robot._data.computed_torque[:, 0].clone())
cmd2.append(new_pos[:, 0].clone().numpy())
data2.append(robot.data.joint_pos[:, 0].clone().numpy())
if count % 10 == 0:
print(f"command pos: {new_pos[:, 0].clone()}, actual pos: {data2[-1]}")
robot.write_data_to_sim()
# Perform step
sim.step()
# Increment counter
count += 1
# Update buffers
robot.update(sim_dt)
robot.reset()
import matplotlib.pyplot as plt
import pandas as pd
csv = pd.read_csv("C:/Users/VR2/Downloads/chirp_response.csv")
column1 = csv.iloc[:, 0]
column2 = np.array(csv.iloc[:, 1])
column3 = np.array(csv.iloc[:, 2])
fig, (ax1, ax2, ax3, ax4) = plt.subplots(1, 4, figsize=(10, 4))
#fig, (ax1, ax2) = plt.subplots(1, 2, figsize=(10, 4))
ax1.plot(data2, label='actual sim')
ax1.plot(cmd2, label='command sim', alpha=0.5)
ax1.plot(column2, label='actual real', alpha=0.5)
ax1.plot(column3, label='command real')
csv = pd.read_csv("C:/Users/VR2/Downloads/step_response.csv")
column1 = csv.iloc[:, 0]
column2 = np.array(csv.iloc[:, 1])
column3 = np.array(csv.iloc[:, 2])
ax2.plot(data, label='actual sim')
ax2.plot(cmd, label='command sim', alpha=0.5)
ax2.plot(column2, label='actual real', alpha=0.5)
ax3.plot(tau_target, label='step requested torque')
ax4.plot(tau_target2, label='chirp requested torque')
ax2.plot(column3, label='command real')
plt.legend()
plt.show()
def main():
"""Main function."""
# Load kit helper
sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005, render_interval=1)
sim = SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
# Design scene
scene_entities, scene_origins = design_scene()
scene_origins = torch.tensor(scene_origins, device=sim.device)
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, scene_entities, scene_origins)
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close() |
Beta Was this translation helpful? Give feedback.
-
Use IdealPdActuator to ensure consistency between simulators. If your gains are the one of the real system, make sure you added the proper |
Beta Was this translation helpful? Give feedback.
-
@vicltz Well, that's the issue...changing friction and armature parameters to estimated values from data collection doesn't give accurate results for any actuator model in Isaac Lab. My experience has been that I can never achieve my goal position at any PD, friction, and armature values with low velocity and effort limits. |
Beta Was this translation helpful? Give feedback.
-
Thank you for following up. I'll move this post to our Discussions section for the team to follow up. |
Beta Was this translation helpful? Give feedback.
-
Hi @Jdowdy05! I am trying something similar for my robot. Were you able to find a solution to this? |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
-
Question
I am using Isaac Lab 2.0.2 and Isaac Sim 4.5.0
I am PD tuning the Dynamixel XM430-W350 actuators in Isaac Sim/Lab for the Robotis OP3. Using real-world values for the actuator in any of the actuator configs doesn't give usable results. One example is that increasing my P gain (stiffness) doesn't change my rise time and drastically increases my steady-state error, which I show plots of below. This was using the ideal PD actuator and uses values taken from the spec sheet of the actuator, though I've also tried changing these, and I still cannot achieve the usable results. This doesn't happen with the implicit actuator; however, this just instantaneously achieves the goal position. I can technically achieve real-world performance, but only when torque and velocity limits are 1e+20, but using this for RL leads my small humanoid learning to fly instead of walk. Is this an issue with Isaac sim/lab actuators, or something wrong on my end?
A few other things I have tried are:
stiffness at 100

stiffness at 20
)
(
stiffness at 1

Beta Was this translation helpful? Give feedback.
All reactions