Set Joint Positions
SUMMARY
Set Joint Positions commands the robot to a target joint configuration (degrees, length equal to the robot's DOF).
SUPPORTED ROBOTS
Available on all supported manipulators in offline mode. Hardware execution is currently supported only on Universal Robots.
UNITS
joint_positions in degrees, ordered base to wrist. speed in deg/s, acceleration in deg/s².
OFFLINE
To run set_joint_positions purely on the kinematic model and visualize the result in Rerun, follow the Synapse Quickstart - one offline example is shipped for every supported brand.
The Skill
robot.set_joint_positions(
joint_positions=target_joint_positions,
speed=60,
acceleration=80,
asynchronous=False,
)The Code
Safety first!
A real robot will faithfully do whatever you ask of it - so please take a moment to clear the workspace, keep an E-Stop within reach, and be ready to disconnect.
Operating real hardware is at your own risk.
Example 1: Basic Move to an Absolute Joint Target
"""
Set Joint Positions example for the Synapse SDK.
Drives the robot to a target joint configuration. Currently supported
only for Universal Robots (UR10e).
For offline, refer to quick start examples.
Usage:
python set_joint_positions.py --ip <ROBOT_IP>
"""
import argparse
from telekinesis.synapse.robots.manipulators import universal_robots
def main(robot_ip: str):
"""
Main function to demonstrate how to create an instance of a robot using the Universal Robots module in Python.
Args:
robot_ip (str): The IP address of the UR robot
Returns:
None
Raises:
None
"""
# Create robot instance
robot = universal_robots.UniversalRobotsUR10E()
# Connect to the robot
robot.connect(ip="192.168.1.2")
# Move to target joint positions
robot.set_joint_positions(
joint_positions=[0, -90, 90, 0, 0, 0],
speed=60,
acceleration=80,
asynchronous=False,
)
# Disconnect
robot.disconnect()
if __name__ == "__main__":
# args parser to get ip
parser = argparse.ArgumentParser(description="UR10e robot set joint positions example")
parser.add_argument("--ip", type=str, default="192.168.1.2", help="IP address of the UR robot")
args = parser.parse_args()
main(args.ip)Example 2: Sequential Relative Joint Moves in sync mode and async mode
"""
Set Joint Positions example for the Synapse SDK.
Drives a real robot to the relative joint positions from current positions in
synchronous mode and back in asynchronous mode.
Currently supported only for Universal Robots (UR10e).
For offline, refer to quick start examples.
Usage:
python set_cartesian_pose.py --ip <ROBOT_IP>
"""
import argparse
from loguru import logger
from telekinesis.synapse.robots.manipulators import universal_robots
def main(robot_ip: str):
"""
Main function to demonstrate how to create an instance of a robot using the Universal Robots module in Python.
Args:
robot_ip (str): The IP address of the UR robot
Returns:
None
Raises:
None
"""
# Create robot instance
robot = universal_robots.UniversalRobotsUR5()
# Connect to the robot
robot.connect(ip=robot_ip)
# Get initial joint positions
initial_joint_positions = robot.get_joint_positions()
logger.info(f"Initial joint positions: {initial_joint_positions}")
# Move to target joint positions
new_joint_positions = initial_joint_positions[:]
new_joint_positions[0] -= 5
speed = 20
acceleration = 20
asynchronous = False
# Move to target joint positions
robot.set_joint_positions(
joint_positions=new_joint_positions,
speed=speed,
acceleration=acceleration,
asynchronous=asynchronous,
)
logger.info(f"Moved to target joint positions: {new_joint_positions}")
# Get current joint positions
actual_joint_positions = robot.get_joint_positions()
# Move to target joint positions
new_joint_positions = actual_joint_positions[:]
new_joint_positions[0] += 5
speed = 20
acceleration = 20
asynchronous = True
# Move to target joint positions
robot.set_joint_positions(
joint_positions=new_joint_positions,
speed=speed,
acceleration=acceleration,
asynchronous=asynchronous,
)
robot.stop_joint_motion(stopping_speed=20)
logger.info(f"Stopped joint motion before reaching target joint positions: {new_joint_positions}")
# Disconnect
robot.disconnect()
if __name__ == "__main__":
# args parser to get ip
parser = argparse.ArgumentParser(description="UR5cb robot set joint positions example")
parser.add_argument("--ip", type=str, required=True, help="IP address of the UR robot")
args = parser.parse_args()
main(args.ip)Example 3: Live Visualization in Rerun
"""Drive a real UR10e through advanced joint-position moves, with a live Rerun feed.
Connects to a UR10e (or URSim) over RTDE, then runs two example moves:
- Example 1: synchronous move of -5° on joint 0 (blocks until complete).
- Example 2: synchronous move of +5° on joint 0 (blocks until complete).
Currently supported only for Universal Robots (UR10e).
For offline, refer to quick start examples.
Install:
pip install rerun-sdk==0.31 # tested on 0.31
Run (replace ``192.168.x.y`` with your UR10e or URSim IP):
python examples/skills/synapse/motion/set_joint_positions_advanced_with_visualization.py --ip 192.168.x.y
"""
import argparse
import time
import numpy as np
import rerun as rr
from loguru import logger
from telekinesis.synapse import utils
from telekinesis.synapse.robots.manipulators import universal_robots
def _visualize_robot(robot, static_meshes: bool = False) -> None:
"""Log per-link transforms to rerun, plus the static meshes on the first call."""
if static_meshes:
for link, m in robot.get-visual-meshes-data().items():
if m["vertices"] is None:
continue
kwargs: dict = {
"vertex_positions": m["vertices"],
"triangle_indices": m["triangles"],
"vertex_normals": m["vertex_normals"],
}
if m["vertex_colors"] is not None:
kwargs["vertex_colors"] = m["vertex_colors"]
else:
kwargs["albedo_factor"] = m["color"] or [179, 179, 179]
rr.log(f"/robot/{link}", rr.Mesh3D(**kwargs), static=True)
for link, transformation_mat in robot.get-visual-mesh-transforms().items():
rr.log(
f"/robot/{link}",
rr.Transform3D(
translation=transformation_mat[:3, 3],
mat3x3=transformation_mat[:3, :3],
),
)
def _visualize_target_joints(robot, path: str, joint_positions, axis_length: float = 0.1) -> None:
"""Forward-kinematic the target joint config and draw the resulting TCP frame."""
target_pose = robot.forward_kinematics(joint_positions)
transformation_mat = np.asarray(
utils.pose_to_transformation_matrix(target_pose, rot_type="deg")
)
origin = transformation_mat[:3, 3]
rr.log(
path,
rr.Arrows3D(
origins=[origin, origin, origin],
vectors=[
transformation_mat[:3, 0] * axis_length,
transformation_mat[:3, 1] * axis_length,
transformation_mat[:3, 2] * axis_length,
],
colors=[[255, 0, 0], [0, 255, 0], [0, 0, 255]],
),
)
def main(ip: str):
"""Move joint 0 by ±60 deg with a live rerun visualization. Supports all robots."""
# Create the robot, initialize rerun, and log the static meshes
robot = universal_robots.UniversalRobotsUR10E()
rr.init(f"telekinesis_synapse_{type(robot).__name__}", spawn=True)
_visualize_robot(robot, static_meshes=True)
time.sleep(2.0)
# Connect to the robot and refresh the visualization with the live state
robot.connect(ip=ip)
_visualize_robot(robot)
# Run two synchronous moves and re-log the robot state after each
try:
# ----- Example 1: synchronous +60 deg on joint 0 -----
delta_deg = 60.0
initial = robot.get_joint_positions()
q_target_1 = list(initial)
q_target_1[0] += delta_deg
_visualize_target_joints(robot, "/target_joints_1", q_target_1)
# Command the joint move and refresh the visualization
robot.set_joint_positions(joint_positions=q_target_1,
speed=20,
acceleration=20,
asynchronous=False)
_visualize_robot(robot)
logger.success(f"Moved to {q_target_1}")
# ----- Example 2: synchronous -60 deg on joint 0 -----
current = robot.get_joint_positions()
q_target_2 = list(current)
q_target_2[0] -= delta_deg
_visualize_target_joints(robot, "/target_joints_2", q_target_2)
# Command the joint move and refresh the visualization
robot.set_joint_positions(joint_positions=q_target_2,
speed=20,
acceleration=20,
asynchronous=False)
_visualize_robot(robot)
logger.success(f"Moved to {q_target_2}")
# Ensure we stop the robot and disconnect even if there was an error
finally:
robot.disconnect()
if __name__ == "__main__":
parser = argparse.ArgumentParser(
description="Set Joint Positions with rerun visualization Synapse example"
)
parser.add_argument("--ip", type=str, required=True, help="Robot IP address")
args = parser.parse_args()
main(ip=args.ip)The Explanation of the Code
from telekinesis.synapse.robots.manipulators import universal_robots
robot = universal_robots.UniversalRobotsUR10E()Create the robot. UR10e is used here for illustration; the same pattern works for every supported brand.
robot.connect(ip="192.168.1.2")Connect to the robot at the given IP - required for hardware execution.
robot.set_joint_positions(
joint_positions=[0, -90, 90, 0, 0, 0],
speed=60,
acceleration=80,
asynchronous=False,
)Drive the robot to the target joint configuration. joint_positions is in degrees (length equal to the robot's DOF), speed in deg/s, acceleration in deg/s². With asynchronous=False the call blocks until the move completes; pass asynchronous=True to return immediately and interrupt later with Stop Joint Motion.
robot.disconnect()Release the controller link once the move is done.
How to Tune the Parameters
| Parameter | Type | Default | Description |
|---|---|---|---|
joint_positions | list[float] | np.ndarray | - | Target joint angles in degrees. Length must equal the robot's DOF. |
speed | float | 60 | Joint speed in deg/s. Start conservative (20-30) when validating a new trajectory; raise once the path is verified. |
acceleration | float | 80 | Joint acceleration in deg/s². Tune in tandem with speed. |
asynchronous | bool | False | If True, the call returns immediately. Use Stop Joint Motion to interrupt the move before it completes. |
WARNING
Passing joint positions outside the robot's joint limits will raise a ValueError or be rejected by the controller. Validate target angles with In Joint Limits before commanding motion, and wrap the call in a try/except block in production code.
Where to Use the Skill
- Homing and reset - Return the robot to a known safe configuration between tasks.
- State transitions - Move to a pre-grasp or pre-place configuration before initiating a Cartesian move.
- Deterministic positioning - Reproduce an exact joint configuration recorded during teach-in.
- Joint-space sequencing - Chain joint-space waypoints to build a repeatable motion sequence.
When Not to Use the Skill
- The target is defined in Cartesian space - use Set Cartesian Pose or Inverse Kinematics to convert first.
- A straight-line TCP path is required - joint-space interpolation does not guarantee a linear tool path; use Set Cartesian Pose instead.
- Collision avoidance along the path is needed - joint-space moves do not account for obstacles; plan the trajectory upstream before commanding motion.

