Hi @zhaowentao, thank you for posting your question. The reason why the spherical joints are not exhibiting elastic behavior is because Joint Drive is not currently enabled for Spherical Joints, only for Revolute, Prismatic and 6D joints.
I actually adapted one of my rope scripts to try to simulate what you are trying to do. Here is the outcome I am getting.
This is the script I am using:
#!/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 how to create a cable/rope mechanism using individual prims.
The rope is made of rigid body capsules connected with spherical joints.
"""
from isaacsim import SimulationApp
# Launch Isaac Sim
simulation_app = SimulationApp({"headless": False})
import time
from pxr import Usd, UsdGeom, UsdPhysics, Gf, Sdf, PhysxSchema, UsdShade, UsdLux
from omni.physx.scripts import physicsUtils
from omni.timeline import get_timeline_interface
from isaacsim.core.api import World
from isaacsim.core.utils.prims import get_prim_at_path
# Set Light stage to Grey Studio
stage = simulation_app.context.get_stage()
light_stage = stage.GetPrimAtPath("/Environment")
if not light_stage:
light_stage = stage.DefinePrim("/Environment", "Xform")
# Create Grey Studio lighting environment
dome_light = UsdLux.DomeLight.Define(stage, "/Environment/GreyStudio")
dome_light.CreateIntensityAttr().Set(1000.0)
class SphericalJoint:
def __init__(self, stage, joint_path, body0_path, body1_path, local_pos0, local_pos1, damping=0.0, stiffness=0.0):
self.stage = stage
self.joint_path = joint_path
self.body0_path = body0_path
self.body1_path = body1_path
self.local_pos0 = local_pos0
self.local_pos1 = local_pos1
self.damping = damping
self.stiffness = stiffness
self.joint = None
self._create_joint()
def _create_joint(self):
# Create a D6 joint
self.joint = UsdPhysics.Joint.Define(self.stage, self.joint_path)
joint_prim = self.joint.GetPrim()
# Lock all translational degrees of freedom
for axis in ["transX", "transY", "transZ", "rotX"]:
limitAPI = UsdPhysics.LimitAPI.Apply(joint_prim, axis)
limitAPI.CreateLowAttr(1.0)
limitAPI.CreateHighAttr(-1.0)
# Set the bodies to connect
self.joint.GetBody0Rel().SetTargets([self.body0_path])
self.joint.GetBody1Rel().SetTargets([self.body1_path])
# Set local positions
self.joint.CreateLocalPos0Attr().Set(self.local_pos0)
self.joint.CreateLocalPos1Attr().Set(self.local_pos1)
# Set local rotations (identity quaternions)
self.joint.CreateLocalRot0Attr().Set(Gf.Quatf(1.0))
self.joint.CreateLocalRot1Attr().Set(Gf.Quatf(1.0))
# Configure joint drives for Y and Z rotation
for axis in ["rotY", "rotZ"]:
limitAPI = UsdPhysics.LimitAPI.Apply(joint_prim, axis)
limitAPI.CreateLowAttr(-1)
limitAPI.CreateHighAttr(1)
driveAPI = UsdPhysics.DriveAPI.Apply(joint_prim, axis)
driveAPI.CreateTypeAttr("force")
driveAPI.CreateDampingAttr(self.damping)
driveAPI.CreateStiffnessAttr(self.stiffness)
def get_joint(self):
return self.joint
class RopeObject:
def __init__(self, stage, default_prim_path, physics_material_path, pivot_point=None,
link_half_length=0.1, rope_length=2.0,
rope_color=None, rope_damping=100.0, rope_stiffness=0.0, contact_offset=0.01, rope_segment_mass=0.001):
self.stage = stage
self.default_prim_path = default_prim_path
self.physics_material_path = physics_material_path
self.pivot_point = pivot_point if pivot_point is not None else Gf.Vec3f(0.0, 0.0, 1.0)
# Configure rope parameters
self.link_half_length = link_half_length
self.link_radius = 0.5 * self.link_half_length
self.rope_length = rope_length
self.rope_color = rope_color if rope_color is not None else Gf.Vec3f(0.2, 0.6, 0.8) # Blue-ish color
self.rope_damping = rope_damping
self.rope_stiffness = rope_stiffness
self.rope_segment_mass = rope_segment_mass
self.contact_offset = contact_offset
# Store segment prims and joints for the rope
self.segments = [] # List of segment prims
self.joints = [] # List of joint prims
def create_segment(self, path, position):
segment_geom = UsdGeom.Capsule.Define(self.stage, path)
segment_geom.CreateHeightAttr(self.link_half_length)
segment_geom.CreateRadiusAttr(self.link_radius)
segment_geom.CreateAxisAttr("X")
segment_geom.CreateDisplayColorAttr().Set([self.rope_color])
# Set position
segment_geom.AddTranslateOp().Set(position)
UsdPhysics.CollisionAPI.Apply(segment_geom.GetPrim())
UsdPhysics.RigidBodyAPI.Apply(segment_geom.GetPrim())
mass_api = UsdPhysics.MassAPI.Apply(segment_geom.GetPrim())
mass_api.CreateMassAttr().Set(self.rope_segment_mass)
physx_collision_api = PhysxSchema.PhysxCollisionAPI.Apply(segment_geom.GetPrim())
physx_collision_api.CreateRestOffsetAttr().Set(0.0)
physx_collision_api.CreateContactOffsetAttr().Set(self.contact_offset)
physicsUtils.add_physics_material_to_prim(self.stage, segment_geom.GetPrim(), self.physics_material_path)
return segment_geom
def create_joint(self, joint_path, body0_path, body1_path, local_pos0, local_pos1):
# Create a spherical joint using the new abstraction
spherical_joint = SphericalJoint(
self.stage,
joint_path,
body0_path,
body1_path,
local_pos0,
local_pos1,
damping=self.rope_damping,
stiffness=self.rope_stiffness
)
return spherical_joint.get_joint()
def create_rope(self):
# Calculate spacing and dimensions
link_length = 2.0 * self.link_half_length
num_links = int(self.rope_length / link_length)
scope_path = self.default_prim_path.AppendChild("Rope")
UsdGeom.Scope.Define(self.stage, scope_path)
y = self.pivot_point[1] # Use pivot point's y coordinate
z = self.pivot_point[2] # Use pivot point's z coordinate
# Create all capsule links
for link_ind in range(num_links):
x = self.pivot_point[0] + link_ind * link_length # Start from pivot point's x coordinate
position = Gf.Vec3f(x, y, z)
capsule_path = scope_path.AppendChild(f"capsule_{link_ind}")
capsule_geom = self.create_segment(capsule_path, position)
self.segments.append(capsule_geom.GetPrim())
# Create joints between consecutive capsules
joint_x = self.link_half_length
for link_ind in range(num_links - 1):
joint_path = scope_path.AppendChild(f"joint_{link_ind}")
body0_path = self.segments[link_ind].GetPath()
body1_path = self.segments[link_ind + 1].GetPath()
local_pos0 = Gf.Vec3f(joint_x, 0, 0)
local_pos1 = Gf.Vec3f(-joint_x, 0, 0)
# joint = self.create_joint(joint_path, body0_path, body1_path, local_pos0, local_pos1)
joint = SphericalJoint(self.stage,
joint_path,
body0_path, body1_path, local_pos0,
local_pos1, damping=self.rope_damping, stiffness=self.rope_stiffness)
joint_prim = joint.get_joint()
self.joints.append(joint_prim)
def get_segments(self):
"""Get all segment prims for the rope"""
return self.segments
def get_joints(self):
"""Get all joint prims for the rope"""
return self.joints
def get_first_segment(self):
"""Get the first segment prim for the rope"""
return self.segments[0] if self.segments else None
def get_last_segment(self):
"""Get the last segment prim for the rope"""
return self.segments[-1] if self.segments else None
# Create a world
my_world = World(stage_units_in_meters=1.0)
# Add default ground plane
my_world.scene.add_default_ground_plane()
# Get the stage
stage = simulation_app.context.get_stage()
# Enable Physics
scene = UsdPhysics.Scene.Define(stage, "/physicsScene")
scene.CreateGravityDirectionAttr().Set(Gf.Vec3f(0.0, 0.0, -1.0))
scene.CreateGravityMagnitudeAttr().Set(9.81)
physx_scene = PhysxSchema.PhysxSceneAPI.Apply(stage.GetPrimAtPath("/physicsScene"))
physx_scene.GetTimeStepsPerSecondAttr().Set(120)
# Create default prim and physics material
default_prim_path = Sdf.Path("/World")
UsdGeom.Xform.Define(stage, default_prim_path)
stage.SetDefaultPrim(stage.GetPrimAtPath(default_prim_path))
# Create the rope creator and generate ropes
physics_material_path = default_prim_path.AppendChild("PhysicsMaterial")
UsdShade.Material.Define(stage, physics_material_path)
material = UsdPhysics.MaterialAPI.Apply(stage.GetPrimAtPath(physics_material_path))
material.CreateStaticFrictionAttr().Set(0.5)
material.CreateDynamicFrictionAttr().Set(0.5)
material.CreateRestitutionAttr().Set(0)
rope_creator = RopeObject(stage,
default_prim_path,
physics_material_path,
pivot_point=Gf.Vec3f(0.0, 0.0, 2.0),
rope_length=2.0,
link_half_length=0.2,
rope_damping=10e6,
rope_stiffness=10e12,
rope_segment_mass=10e-6)
rope_creator.create_rope()
# Create a Fixed Joint between the first capsule and the world
# Get the first capsule path
first_capsule_path = "/World/Rope/capsule_0"
first_segment = rope_creator.get_first_segment()
# Create a fixed joint to anchor the first segment to the world
anchor_joint_path = default_prim_path.AppendChild("anchor_joint")
anchor_joint = UsdPhysics.FixedJoint.Define(stage, anchor_joint_path)
# Set the first segment as body1 (body0 will be the world/ground)
anchor_joint.GetBody0Rel().SetTargets(['/World'])
anchor_joint.GetBody1Rel().SetTargets([first_segment.GetPath()])
# Set the local position for the anchor joint
first_segment_position = first_segment.GetAttribute("xformOp:translate").Get()
anchor_joint.CreateLocalPos0Attr().Set(first_segment_position) # Local position on the first segment
# Initial setup for the simulation
timeline = get_timeline_interface()
# Start the simulation
timeline.play()
# Wait for the simulation to start
while not timeline.is_playing():
simulation_app.update()
time.sleep(0.01)
# Keep the simulation running
print("Simulation started. Press Ctrl+C to exit")
position = 0.0
try:
while timeline.is_playing():
simulation_app.update()
time.sleep(0.01)
except KeyboardInterrupt:
print("Simulation stopped by user")
finally:
# Stop the simulation
timeline.stop()
simulation_app.close()
Hope that helps!