Set Cartesian Pose
SUMMARY
Set Cartesian Pose commands the robot's TCP to a target pose [x, y, z, rx, ry, rz] (meters + Euler XYZ degrees) along a straight Cartesian path.
SUPPORTED ROBOTS
Available on all supported manipulators in offline mode. Hardware execution is currently supported only on Universal Robots.
UNITS
cartesian_pose is [x, y, z, rx, ry, rz] in meters and Euler XYZ degrees. speed in m/s, acceleration in m/s².
OFFLINE
To run set_cartesian_pose 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_cartesian_pose(
cartesian_pose=target_pose,
speed=0.25,
acceleration=0.25,
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 Target Cartesian Pose
"""
Set Cartesian Pose example for the Synapse SDK.
Drives a real UR10e to the target Cartesian pose. This example is for real robot.
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 set_cartesian_pose(robot_ip: str):
"""Move the TCP to a target Cartesian pose on a connected UR10e."""
# Create robot instance
robot = universal_robots.UniversalRobotsUR10E()
# Define target Cartesian pose [x, y, z (m), rx, ry, rz (deg)]
target_pose = [0, 0.65, 0.85, 180, 0, 90]
# Safety warning before commanding real motion
logger.warning(
f"About to move real robot to target pose {target_pose}. "
"Make sure it's safe to move there, otherwise use the advanced example."
)
# Connect to the robot
robot.connect(ip=robot_ip)
# Command the move, then disconnect cleanly
try:
robot.set_cartesian_pose(
cartesian_pose=target_pose,
speed=0.1,
acceleration=0.1,
)
logger.info(f"Moved to target Cartesian pose: {target_pose}")
finally:
robot.disconnect()
def main():
"""Run the set_cartesian_pose Synapse example."""
parser = argparse.ArgumentParser(description="UR10e set_cartesian_pose example")
parser.add_argument("--ip", type=str, required=True, help="IP address of the UR robot")
args = parser.parse_args()
# Run the example
set_cartesian_pose(robot_ip=args.ip)
if __name__ == "__main__":
main()Example 2: Synchronous and Asynchronous Relative Moves
"""
Set Cartesian Pose example for the Synapse SDK.
Drives a real robot to the relative pose from current pose.
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
import time
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.UniversalRobotsUR10E()
# Connect to the robot
robot.connect(ip=robot_ip)
# Example 1
# Get initial Cartesian pose
initial_tcp_pose = robot.get_cartesian_pose()
# Move to target Cartesian pose
new_tcp_pose = initial_tcp_pose[:]
new_tcp_pose[2] -= 0.2
tcp_speed = 0.25
tcp_acceleration = 0.25
asynchronous = False
# Move to target Cartesian pose
robot.set_cartesian_pose(
cartesian_pose=new_tcp_pose,
speed=tcp_speed,
acceleration=tcp_acceleration,
asynchronous=asynchronous,
)
logger.info(f"Moved to target Cartesian pose: {new_tcp_pose}")
# Example 2: Async
# Get initial Cartesian pose
actual_tcp_pose = robot.get_cartesian_pose()
# Move to target Cartesian pose
new_tcp_pose = actual_tcp_pose[:]
new_tcp_pose[2] += 0.2
tcp_speed = 0.25
tcp_acceleration = 0.25
stopping_speed = 0.25
asynchronous = False
# Move to target Cartesian pose
robot.set_cartesian_pose(
cartesian_pose=new_tcp_pose,
speed=tcp_speed,
acceleration=tcp_acceleration,
asynchronous=asynchronous,
)
time.sleep(0.5)
robot.stop_cartesian_motion(stopping_speed=stopping_speed)
logger.info(f"Stopped Cartesian motion before reaching target Cartesian pose: {new_tcp_pose}")
# Disconnect
robot.disconnect()
if __name__ == "__main__":
# args parser to get ip
parser = argparse.ArgumentParser(description="UR10e robot movel 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 3: Live Visualization in Rerun
"""Drive a real UR10e through advanced Cartesian moves, with a live Rerun feed.
Connects to a UR10e, then runs two example moves:
- Example 1: synchronous move -20cm in Z (blocks until complete).
- Example 2: asynchronous move +20cm in Z, stopped after 0.5s with
``stop_cartesian_motion`` before it reaches the target.
Each example draws the target TCP frame in rerun (RGB axis arrows) and
the live robot state is streamed throughout the async move.
Make sure the cell is clear and the robot is in remote-control mode
before running.
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_cartesian_pose_advanced_with_visualization.py --ip 192.168.x.y
"""
import argparse
import time
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_frame(path: str, pose, axis_length: float = 0.1) -> None:
"""Draw a 6-vec pose [x, y, z, rx, ry, rz] (deg) as RGB axis arrows.
Columns of the rotation matrix are the world-frame X/Y/Z axis vectors.
Red -> X, Green -> Y, Blue -> Z.
"""
transformation_mat = utils.pose_to_transformation_matrix(pose, "deg")
origin = transformation_mat[:3, 3]
rr.log(
path,
rr.Arrows3D(
origins=[origin, origin, origin],
vectors=[
transformation_mat[:3, 0] * axis_length, # X axis
transformation_mat[:3, 1] * axis_length, # Y axis
transformation_mat[:3, 2] * axis_length, # Z axis
],
colors=[[255, 0, 0], [0, 255, 0], [0, 0, 255]],
),
)
def main(robot_ip: str):
"""Connect to a UR10e and run the synchronous + asynchronous Cartesian demos."""
# Create the robot instance
robot = universal_robots.UniversalRobotsUR10E()
# Initialize rerun and log static meshes
rr.init(f"telekinesis_synapse_{type(robot).__name__}", spawn=True)
visualize_robot(robot, static_meshes=True)
time.sleep(2.0)
# Connect to the robot
logger.info(f"Connecting to UR10e at {robot_ip}...")
robot.connect(ip=robot_ip)
visualize_robot(robot)
try:
# ----- Example 1: synchronous move -20cm in Z -----
delta_z = 0.2
initial_tcp_pose = robot.get_cartesian_pose()
new_tcp_pose = initial_tcp_pose[:]
new_tcp_pose[2] -= delta_z
visualize_target_frame("/target_pose_1", new_tcp_pose)
# Move the robot
robot.set_cartesian_pose(
cartesian_pose=new_tcp_pose,
speed=0.25,
acceleration=0.25,
asynchronous=False,
)
visualize_robot(robot)
logger.info(f"Moved to target Cartesian pose: {new_tcp_pose}")
# ----- Example 2: asynchronous move +20cm in Z, stopped after 0.5s -----
actual_tcp_pose = robot.get_cartesian_pose()
new_tcp_pose = actual_tcp_pose[:]
new_tcp_pose[2] += delta_z
visualize_target_frame("/target_pose_2", new_tcp_pose)
# Move the robot
robot.set_cartesian_pose(
cartesian_pose=new_tcp_pose,
speed=0.1,
acceleration=0.1,
asynchronous=True,
)
time.sleep(2)
robot.stop_cartesian_motion(stopping_speed=0.25)
logger.info(f"Stopped Cartesian motion before reaching target Cartesian pose: {new_tcp_pose}")
visualize_robot(robot)
finally:
# Disconnect the robot
logger.info("Disconnecting from UR10e...")
robot.disconnect()
if __name__ == "__main__":
parser = argparse.ArgumentParser(description="UR10e advanced Cartesian example with Rerun viz")
parser.add_argument(
"--ip",
type=str,
required=True,
help="IPv4 address (or hostname) of the UR10e controller",
)
args = parser.parse_args()
main(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=robot_ip)Connect to the robot at the given IP - required for hardware execution.
robot.set_cartesian_pose(
cartesian_pose=target_pose,
speed=0.1,
acceleration=0.1,
)Drive the TCP to [x, y, z, rx, ry, rz] along a straight Cartesian path. With asynchronous=False (default) the call blocks until the move completes; pass asynchronous=True to return immediately and interrupt later with Stop Cartesian Motion.
finally:
robot.disconnect()Release the controller link in a finally block so a fault mid-motion still cleans up the connection.
How to Tune the Parameters
| Parameter | Type | Default | Description |
|---|---|---|---|
cartesian_pose | list[float] | np.ndarray | - | Target pose [x, y, z, rx, ry, rz]. Position in meters; orientation as Euler XYZ in degrees. |
speed | float | 1.05 | TCP speed in m/s. Keep low (0.05-0.25) during contact tasks and near obstacles; increase only after validating the path. |
acceleration | float | 1.4 | TCP acceleration in m/s². Tune in tandem with speed. |
asynchronous | bool | False | If True, the call returns immediately. Use Stop Cartesian Motion to interrupt the move before it completes. |
WARNING
Poses near kinematic singularities or outside the reachable workspace will raise a RuntimeError. Verify reachability with Inverse Kinematics before commanding motion, and wrap the call in a try/except block in production code.
Where to Use the Skill
- Pick-and-place - Drive the TCP to approach, grasp, and release poses defined in Cartesian space.
- Assembly - Insert a part along a straight-line path in the task frame.
- Tool positioning - Place a welding tip, camera, or sensor at a precise location in the workspace.
- Relative offsets - Apply small corrections (e.g. from vision feedback) by offsetting the current TCP pose.
When Not to Use the Skill
- You need to reach a specific joint configuration - use Set Joint Positions to command joint space directly.
- The target pose is near a kinematic singularity - Cartesian motion through or near a singularity is erratic; replan the path to avoid it.
- Collision avoidance along the straight-line path is required - Cartesian moves do not account for obstacles; plan the trajectory upstream before commanding motion.
- You only know the target in joint space - use Forward Kinematics to convert joints to a pose first.

