Cable-driven parallel robots are formed by replacing rigid links with pulleys and cables on the basis of traditional rigid parallel robots. So, how can the assembly of a cable-driven parallel robot be achieved in Isaac Sim? For example, how can pulleys and cables be generated or designed?
Hi @1335657223,
Here is an example of how to make a cable driven robot using DistanceJoints.
Code to reproduce this:
# 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.
#
from isaacsim import SimulationApp
# Create simulation app (not headless so we can see the simulation)
simulation_app = SimulationApp({"headless": False})
from isaacsim.core.api import World
from isaacsim.core.utils.stage import add_reference_to_stage
import carb
from pxr import UsdGeom, Gf, Sdf, UsdPhysics
import numpy as np
import time
from isaacsim.core.api.objects import DynamicCuboid, DynamicSphere
from isaacsim.core.utils.rotations import euler_angles_to_quat
# Create world with numpy backend
my_world = World(stage_units_in_meters=1.0)
print("Using numpy backend")
# Set the desired time step (240 updates per second for smooth simulation)
desired_time_step = 1.0 / 240.0
my_world.set_simulation_dt(physics_dt=desired_time_step, rendering_dt=desired_time_step)
# Add default ground plane
my_world.scene.add_default_ground_plane()
# Get stage
stage = simulation_app.context.get_stage()
# Define the circle parameters
radius = 0.5 # radius of the circle
height = 2.0 # height of the spheres
center = np.array([0.0, 0.0, height]) # center of the circle
# Calculate positions at 90 degrees intervals around the circle (for 4 spheres)
angle1 = 0 # 0 degrees
angle2 = np.pi / 2 # 90 degrees
angle3 = np.pi # 180 degrees
angle4 = 3 * np.pi / 2 # 270 degrees
# Create the four spheres using DynamicSphere
sphere1 = my_world.scene.add(
DynamicSphere(
name="sphere1",
position=np.array([center[0] + radius * np.cos(angle1), center[1] + radius * np.sin(angle1), center[2]]),
prim_path="/World/Sphere1",
scale=np.array([0.05, 0.05, 0.05]),
color=np.array([1, 0, 0]),
mass=1.0,
)
)
sphere2 = my_world.scene.add(
DynamicSphere(
name="sphere2",
position=np.array([center[0] + radius * np.cos(angle2), center[1] + radius * np.sin(angle2), center[2]]),
prim_path="/World/Sphere2",
scale=np.array([0.05, 0.05, 0.05]),
color=np.array([0, 1, 0]),
mass=1.0,
)
)
sphere3 = my_world.scene.add(
DynamicSphere(
name="sphere3",
position=np.array([center[0] + radius * np.cos(angle3), center[1] + radius * np.sin(angle3), center[2]]),
prim_path="/World/Sphere3",
scale=np.array([0.05, 0.05, 0.05]),
color=np.array([0, 0, 1]),
mass=1.0,
)
)
sphere4 = my_world.scene.add(
DynamicSphere(
name="sphere4",
position=np.array([center[0] + radius * np.cos(angle4), center[1] + radius * np.sin(angle4), center[2]]),
prim_path="/World/Sphere4",
scale=np.array([0.05, 0.05, 0.05]),
color=np.array([1, 0, 1]),
mass=1.0,
)
)
# Create fixed joints to anchor the spheres to the world
# This will prevent the spheres from falling due to gravity
fixed_joints = []
for i, sphere_path in enumerate(["/World/Sphere1", "/World/Sphere2", "/World/Sphere3", "/World/Sphere4"]):
joint_path = f"/World/FixedJoint{i+1}"
fixed_joint = UsdPhysics.FixedJoint.Define(stage, joint_path)
fixed_joint.CreateBody0Rel().AddTarget("/World")
fixed_joint.CreateBody1Rel().AddTarget(sphere_path)
fixed_joints.append(fixed_joint)
# Create the cuboid centered between the spheres but at a lower height
cuboid = my_world.scene.add(
DynamicCuboid(
name="cuboid",
position=np.array([0.0, 0.0, 2.0]),
prim_path="/World/Cuboid",
scale=np.array([0.5, 0.5, 0.2]),
color=np.array([1, 1, 0]),
mass=1.0,
)
)
# Create distance joints to connect each sphere to the cuboid
# These will act like cables connecting the spheres to the cuboid
distance_joints = []
angles = [angle1, angle2, angle3, angle4]
sphere_paths = ["/World/Sphere1", "/World/Sphere2", "/World/Sphere3", "/World/Sphere4"]
for i, (angle, sphere_path) in enumerate(zip(angles, sphere_paths)):
joint_path = f"/World/DistanceJoint{i+1}"
distance_joint = UsdPhysics.DistanceJoint.Define(stage, joint_path)
distance_joint.CreateBody0Rel().AddTarget(sphere_path)
distance_joint.CreateBody1Rel().AddTarget("/World/Cuboid")
# Set the minimum and maximum distance for the joint
distance_joint.CreateMinDistanceAttr().Set(0.0) # Minimum distance
distance_joint.CreateMaxDistanceAttr().Set(0.5) # Maximum distance
# Position the anchor point at the perimeter of a circle with radius 0.5
local_pos = Gf.Vec3f(0.5 * np.cos(angle), 0.5 * np.sin(angle), 0.5)
distance_joint.CreateLocalPos1Attr().Set(local_pos)
distance_joints.append(distance_joint)
# Reset world to initialize scene
my_world.reset()
print("Simulation started. Four spheres are fixed in place with a cuboid suspended by distance joints.")
print("The distance joints will gradually lengthen over time, lowering the cuboid.")
print("Press Ctrl+C to exit.")
start_time = time.time()
simulation_duration = 10.0 # Run for 10 seconds
# Main simulation loop
try:
while simulation_app.is_running():
current_time = time.time() - start_time
# Print positions every second
if int(current_time) != int(current_time - my_world.get_physics_dt()):
cuboid_pos = cuboid.get_world_pose()[0]
print(f"Time: {current_time:.1f}s - Cuboid height: {cuboid_pos[2]:.3f}m")
# Step the simulation
my_world.step(render=True)
# Oscillate the height of the cube between 0.5 and 2.0
# Use a sine wave to create smooth oscillation
oscillation_frequency = 0.1 # Hz (complete cycle every 2 seconds)
min_height = 0.5
max_height = 1.0
height_range = max_height - min_height
# Calculate the oscillating scale factor based on sine wave
scale_factor = min_height + height_range * (0.5 + 0.5 * np.sin(2 * np.pi * oscillation_frequency * current_time))
# Update the maximum distance for each distance joint
for joint in distance_joints:
joint.GetMaxDistanceAttr().Set(scale_factor)
# Print the current max distance every second
if int(current_time) != int(current_time - my_world.get_physics_dt()):
print(f"Time: {current_time:.1f}s - Max distance set to: {scale_factor:.3f}m")
except KeyboardInterrupt:
print("Simulation stopped by user")
finally:
# Cleanup
simulation_app.close()
The example is not transforming cube position to distance joint length. To figure that our you will either need to compute inverse kinematics or compute the Jacobian. Hopefully this is a good start for you.
Michael
This topic was automatically closed after 2 days. New replies are no longer allowed.