robots_rtde
UR10 robot interface using the UR RTDE protocol.
This module provides a high-level ur10 robot class built on RobotBlockSet, wrapping Universal Robots’ RTDE control, receive, IO, and dashboard interfaces. It also defines status codes and helpers for interpreting robot and safety state.
- class robotblockset.ur.robots_rtde.URStatusCode(*values)[source]
Bases:
IntEnumStatus and error codes used by the UR RTDE robot interface.
- OK = 0
- NOT_CONNECTED = 10
- EMERGENCY_STOP = 20
- PROTECTIVE_STOP = 21
- SAFEGUARD_STOP = 22
- SAFETY_FAULT = 23
- SAFETY_VIOLATION = 24
- SAFETY_STOPPED = 25
- RECOVERY_MODE = 30
- POWER_OFF = 31
- POWER_ON_NO_MOTION = 32
- BACKDRIVE = 33
- DISCONNECTED = 34
- NO_CONTROLLER = 35
- BOOTING = 36
- UPDATING_FIRMWARE = 37
- REDUCED_MODE = 90
- class robotblockset.ur.robots_rtde.robot_ur_rtde(robot_name: str, host: str = '192.168.56.101')[source]
Bases:
robotHigh-level interface for UR robots using the RTDE protocol.
This class integrates the Universal Robots RTDE (Real-Time Data Exchange) interfaces for control, monitoring, and IO with the RobotBlockSet framework. It enables commanding joint or Cartesian motion, monitoring robot status, performing force control, and interacting with the dashboard client.
- Parameters:
robot_name (str) – Name of the robot instance, used for logging and identification.
host (str, optional) – IP address of the UR robot controller. Default is
"192.168.56.101".
- Attributes:
Name (str) – Name of the robot instance.
tsamp (float) – Sampling time used for RTDE servoing commands (typically
1/125 s).velocity (float) – Default motion speed scaling factor (0–1).
acceleration (float) – Default acceleration scaling factor (0–1).
lookahead_time (float) – Lookahead time for RTDE servoing.
gain (float) – Gain applied to RTDE servoing.
rtde_c (RTDEControl) – RTDE control interface instance.
rtde_r (RTDEReceive) – RTDE receive (state feedback) interface instance.
rtde_i (RTDEIO) – RTDE IO interface instance.
dash_c (DashboardClient) – Dashboard interface for higher-level controller actions.
Notes
Control commands are sent using the RTDE protocol at real-time rates.
Cartesian pose commands are automatically mapped to the robot base frame.
Force mode allows compliant movement based on external wrench feedback.
The robot must be powered on with drives enabled before motion commands.
Safety states and error codes can be interpreted using Check().
Create a UR robot interface using the RTDE protocol.
- Parameters:
robot_name (str) – Name of the robot instance, used for logging and identification.
host (str, optional) – IP address of the UR robot controller. Default is
"192.168.56.101".
- Returns:
This constructor initializes the RTDE robot interface in place.
- Return type:
None
- __init__(robot_name: str, host: str = '192.168.56.101') None[source]
Create a UR robot interface using the RTDE protocol.
- Parameters:
robot_name (str) – Name of the robot instance, used for logging and identification.
host (str, optional) – IP address of the UR robot controller. Default is
"192.168.56.101".
- Returns:
This constructor initializes the RTDE robot interface in place.
- Return type:
None
- GetState() None[source]
Read and cache the current robot state.
- Returns:
This method refreshes the internal joint, Cartesian, and wrench state.
- Return type:
None
- AvailableStrategies() List[str][source]
Get the available control strategies for the robot.
- Returns:
Names of the supported control strategies.
- Return type:
List[str]
- SetStrategy(strategy: str) None[source]
Set the control strategy for the robot.
- Parameters:
strategy (str) – Control strategy to activate.
- Returns:
This method updates the active control strategy.
- Return type:
None
- SetTeachMode() None[source]
Enable teach mode on the robot.
- Returns:
This method enables hand-guiding mode through RTDE.
- Return type:
None
- EndTeachMode() None[source]
Disable teach mode on the robot.
- Returns:
This method restores the standard robot control mode.
- Return type:
None
- isConnected() bool[source]
Checks if the robot is connected.
- Returns:
True if the robot is connected, False otherwise.
- Return type:
bool
- Connect() bool[source]
Attempt to reconnect to the robot dashboard interface.
- Returns:
Trueif the reconnection was successful,Falseif it failed.- Return type:
bool
Notes
Only reconnects the dashboard client, not RTDE interfaces.
Use this when communication was interrupted.
For a full reconnection of all interfaces, use a dedicated restart method.
- Disconnect() None[source]
Disconnect all active RTDE and dashboard connections.
This method sequentially terminates communication with: - RTDE control interface - RTDE receive interface - RTDE I/O interface - Dashboard client
- Returns:
This method closes all active RTDE and dashboard connections.
- Return type:
None
Notes
After calling this, no robot commands can be executed until a proper reconnection is made.
Recommended to call before shutting down the application.
- isReady() bool[source]
Check if the robot is ready for operations.
This method checks the _connected attribute to determine if the robot is connected and operational.
- Returns:
True if the robot is connected and ready for operations, otherwise False.
- Return type:
bool
- inMotion() bool[source]
Check if the robot is in motion.
- Returns:
True if the robot is in motion.
- Return type:
bool
Notes
This function will always return True in modes other than the standard position mode, e.g. in force and teach mode.
- isAsynchronousMotionRunning() bool[source]
Check if the robot is currently executing an asynchronous operation.
- Returns:
True if an asynchronous operation is running, False otherwise.
- Return type:
bool
Notes
Asynchronous operations include non-blocking movements or actions initiated through the RTDE interface.
This method relies on the RTDE control interface’s ability to report the status of asynchronous operations.
- PowerOn() None[source]
Power on the robot arm.
Sends a command to the robot controller to enable power to the actuators. The robot remains stationary until brakes are released or motion is commanded.
- Return type:
None
Notes
This does not automatically release the brakes.
To enable motion, call
BreakRelease()afterward.
- PowerOff() None[source]
Power off the robot arm.
Disables actuator power and stops any ongoing motion immediately.
- Return type:
None
Notes
Should only be used when the robot is in a safe state.
The brakes will engage automatically to hold position.
- BreakRelease() None[source]
Release the robot arm brakes.
Enables movement of the robot after powering on. This allows motion commands to be executed. Required after calling
PowerOn().- Return type:
None
Notes
The robot must be powered on first via
PowerOn().Use with caution—ensure the robot is in a safe environment.
- CheckStatus(silent: bool = False) tuple[source]
Check the current status of the robot.
- Parameters:
silent (bool, optional) – If True, suppress status messages.
- Returns:
Status code and a list of short human-readable status descriptions.
- Return type:
tuple[URStatusCode, list[str]]
Note
When not silent it prints detailed multi-line status & recovery hints.
- Check(silent: bool = False) list[source]
Return human-readable robot status messages.
- Parameters:
silent (bool, optional) – If True, suppress status messages.
- Returns:
Short human-readable status descriptions.
- Return type:
list[str]
Note
When not silent it prints detailed multi-line status & recovery hints.
- ErrorRecovery() bool[source]
Attempt to recover the robot from common recoverable errors.
- Returns:
True if recovery succeeded or no recovery was required, else False.
- Return type:
bool
- InternalStopMotion() None[source]
Internal method to stop the robot motion immediately.
This method sends a stop command to the robot controller to halt all ongoing movements. It is intended for use within motion monitoring loops when an abort condition is detected.
- Return type:
None
Notes
Use with caution; ensure the robot is in a safe state before stopping.
This does not perform any additional safety checks or state updates.
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Update joint positions and wait
- Parameters:
q (JointConfigurationType) – desired joint positions (nj, )
qdot (JointVelocityType, optional) – desired joint velocities (nj, )
trq (JointTorqueType, optional) – additional joint torques (nj, )
wait (float, optional) – Maximal wait time since last update. Defaults to 0.
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- JMove(q: ndarray, t: float | None = None, vel: float | None = None, acc: float | None = None, vel_fac: ndarray | None = None, wait: float | None = None, traj: str | None = None, added_trq: ndarray | None = None, min_joint_dist: float | None = None, asynchronous: bool | None = None, use_internal: bool | None = None, **kwargs: Any) Thread | int[source]
Moves the robot to a specified joint position with specified velocity and trajectory.
- Parameters:
q (JointConfigurationType) – Desired joint positions (nj,).
t (float, optional) – Time for the movement, by default None.
vel (float, optional) – Desired velocity for the movement, by default None.
= (acc) – Acceleration for the movement, by default None (uses default acceleration).
vel_fac (JointConfigurationType, optional) – Velocity scaling factor for each joint, by default None.
wait (float, optional) – Time to wait after movement is completed, by default None.
traj (str, optional) – Trajectory type, by default None.
added_trq (JointTorqueType, optional) – Additional joint torques, by default None.
min_joint_dist (float, optional) – Minimum distance to target joint positions for movement execution, by default None.
asynchronous (bool, optional) – If True, executes the movement asynchronously, by default False.
use_internal (bool, optional) – If True, uses internal methods for movement execution, by default False.
**kwargs (dict) – Additional keyword arguments passed to internal methods.
- Returns:
The thread executing the asynchronous movement, or the status code if asynchronous is False.
- Return type:
Union[Thread, int]
Notes
If asynchronous is set to True, the movement will be executed in a separate thread.
The control strategy should be set to “Joint” for this function to work.
- GoTo_T(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Move the robot to the target pose and velocity in Cartesian space.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType]) – Target end-effector pose in Cartesian space. Can be in different forms (e.g., Pose, Transformation matrix).
v (Velocity3DType, optional) – Target end-effector velocity in Cartesian space. Default is a zero velocity vector (6,).
FT (WrenchType, optional) – Target force/torque in Cartesian space. Default is a zero wrench vector (6,).
wait (float, optional) – The time to wait after the movement, by default the sample time (self.tsamp).
**kwargs (dict) – Additional keyword arguments passed to other methods, including task_space.
- Returns:
The status of the move (0 for success, non-zero for error).
- Return type:
int
- Raises:
ValueError – If the provided task space is not supported.
Notes
The method first converts the input x, v, and FT based on the specified task space. The robot will be moved using Cartesian control.
- GoTo_X(x: ndarray, v: ndarray | None = None, FT: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Update task pose and wait
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType]) – Target end-effector pose in Cartesian space. Can be in different forms (e.g., Pose, Transformation matrix).
v (Velocity3DType, optional) – Target end-effector velocity in Cartesian space. Default is a zero velocity vector (6,).
FT (WrenchType, optional) – Target force/torque in Cartesian space. Default is a zero wrench vector (6,).
wait (float, optional) – The time to wait after the movement, by default the sample time (self.tsamp).
control. (The robot will be moved using Cartesian)
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- CMove(x: ndarray, t: float | None = None, vel: float | None = None, acc: float | None = None, vel_fac: float | None = None, traj: str | None = None, short: bool | None = None, wait: float | None = None, task_space: str | None = None, added_FT: ndarray | None = None, state: str = 'Commanded', min_pos_dist: float | None = None, min_ori_dist: float | None = None, asynchronous: bool | None = None, use_internal: bool | None = None, **kwargs: Any) Thread | int[source]
Executes a Cartesian move with specified target position, velocity, and trajectory.
The robot moves its end-effector to a target position with optional velocity, trajectory type, and additional force/torque settings.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType, RotationMatrixType]) – The target Cartesian position (7,) or (4,4) or (3,3), where 7 represents position and orientation, and (4,4) is a homogeneous transformation matrix.
t (float, optional) – The duration for the movement, by default None.
vel (float, optional) – The velocity at which the end-effector moves, by default None.
= (acc) – Acceleration for the movement, by default None (uses default acceleration).
vel_fac (float, optional) – A factor to scale the velocity, by default None.
traj (str, optional) – The trajectory type, by default None.
short (bool, optional) – Whether to shorten the path, by default None.
wait (float, optional) – The wait time after the movement, by default None.
task_space (str, optional) – The task space reference frame, by default None.
added_FT (WrenchType, optional) – Additional force/torque to be applied, by default None.
state (str, optional) – The state of the robot (e.g., “Commanded” or “Actual”), by default “Commanded”.
min_pos_dist (float, optional) – The minimum position distance for stopping, by default None.
min_ori_dist (float, optional) – The minimum orientation distance for stopping, by default None.
asynchronous (bool, optional) – Whether the motion should be performed asynchronously, by default False.
use_internal (bool, optional) – If True, uses internal methods for movement execution, by default False.
**kwargs (dict) – Additional keyword arguments passed to internal methods.
- Returns:
The thread executing the asynchronous movement, or the status code if synchronous.
- Return type:
Union[Thread, int]
- Raises:
ValueError – If an unsupported task space or parameter shape is provided.
- ForceMode(task_frame: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], selection: Iterable[int], FT: ndarray, type: int = 2, limits: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] = (1, 1, 1, 1, 1, 1), task_space: str | None = None) None[source]
Activate Cartesian force control mode.
- Parameters:
task_frame (Union[Pose3DType, HomogeneousMatrixType, RotationMatrixType, Vector3DType, QuaternionType, ArrayLike]) – or as a homogeneous transformation matrix.
selection (Iterable[int]) –
1enables control along the corresponding axis.FT (WrenchType) – Desired force and torque values in the task frame.
type (int, optional) –
An integer [1;3] specifying how the robot interprets the force frame. 1: The force frame is transformed in a way such that its y-axis is
aligned with a vector pointing from the robot tcp towards the origin of the force frame.
2: The force frame is not transformed. 3: The force frame is transformed in a way such that its x-axis
is the projection of the robot tcp velocity vector onto the x-y plane of the force frame.
limits (ArrayLike, optional) – along/about the axis. Default is
[1, 1, 1, 1, 1, 1].task_space (str, optional) – Specifies the space of task_frame. Supported values:
"World","Robot","Object","Tool". IfNone, the robot’s default task space is used.
- Raises:
ValueError – If input has invalid dimension, type, or unsupported options.
Notes
Force control is executed in compliance mode, allowing interaction with the environment. Use
ForceModeStop()to exit force mode safely.
- ForceModeDamping(damping: float = 0.005) None[source]
Set damping for force mode.
- Parameters:
damping (float, optional) – responsiveness but may reduce stability. Default is
0.005.- Raises:
ValueError – If damping is outside allowed range [0, 1].
- ForceModeScaling(scaling: float = 1.0) None[source]
Set gain scaling for force mode.
- Parameters:
scaling (float, optional) – aggressive force application. Default is
1.0.- Raises:
ValueError – If scaling is outside allowed range [0, 2].
- ForceModeStop() None[source]
Exit Cartesian force control mode.
Stops force mode execution, clears popups, reuploads control script, and resets current motion target.
Notes
Recommended to call after force interaction is complete.
Robot may return to non-compliant mode, ensure stability post-contact.
- Contacts(direction: Iterable[float] = (0, 0, 0, 0, 0, 0)) ndarray | None[source]
Detect contact between the robot tool and an external object.
- Parameters:
direction (Iterable[float], optional) –
of contact detection in the robot base coordinate system. - If the first three elements are all zeros (default), contact is detected from all directions. - Elements 4–6 are reserved but must still be provided for compatibility.
Defaults to
(0, 0, 0, 0, 0, 0).- Returns:
An array of historical joint positions up to the point just before contact was detected. - Returns a position history if contact occurred (i.e., result > 0). - Returns
Noneif no contact is detected.- Return type:
JointPathType or None
Notes
Based on RTDE toolContact() detection. A positive return value indicates
the number of cycles back to where the contact started. - The returned joint positions represent the robot pose immediately before impact. - Only works in real robot mode with enabled force sensing. - May require tuned safety settings to trigger detection.
- MoveUntilContact(speed: Iterable[float], direction: Iterable[float] = (0, 0, 0, 0, 0, 0), acceleration: float = 0.5) bool[source]
Move the robot until physical contact is detected.
The robot moves using Cartesian speed control until a collision is detected along a specified direction. After contact, it automatically retracts to the initial point of impact.
- Parameters:
speed (Iterable[float]) – Desired tool (TCP) spatial velocity [vx, vy, vz, wx, wy, wz] in meters per second and radians per second. Must be a 6D vector.
direction (Iterable[float], optional) – Contact detection direction. The first three elements define a 3D vector in the robot base frame for detecting contact forces. - If all three are zero (default), contact is detected from all directions. - You may also pass get_target_tcp_speed() to detect contact in the current movement direction.
acceleration (float, optional) – TCP Cartesian acceleration in m/s². Default is
0.5.
- Returns:
Trueif contact was detected and motion stopped successfully.Falseonly if an internal RTDE failure occurs.- Return type:
bool
- Raises:
ValueError – If speed is not a valid 6D vector.
Notes
The robot automatically retracts slightly upon detection.
This method blocks until contact is detected.
For asynchronous monitoring, use startContactDetection() instead.
Contact detection sensitivity depends on robot configuration and safety settings.
- FreeDrive(free_axes: Iterable[int] = (1, 1, 1, 1, 1, 1), feature: Iterable[float] = (0.0, 0.0, 0.0, 0.0, 0.0, 0.0)) bool[source]
Enable robot freedrive mode (hand-guiding).
In freedrive mode, the robot can be physically guided by hand, similar to pressing the robot’s Freedrive button on the teach pendant. This can be useful for manual positioning, demonstration-based programming, or fine-tuning poses.
- Parameters:
free_axes (Iterable[int], optional) – A 6-element list specifying which axes are free to move: -
1→ Axis enabled for hand-guiding -0→ Axis locked The default(1, 1, 1, 1, 1, 1)enables full 6-DoF movement.feature (Iterable[float], optional) – frame for freedrive constraints. Normally [0, 0, 0, 0, 0, 0]. Only relevant when using constrained freedrive behavior.
- Returns:
Trueif freedrive mode was successfully activated,Falseif activation failed.- Return type:
bool
Notes
While in freedrive mode, the robot cannot execute motion commands
(e.g.,
moveJormoveL). - To exit freedrive mode, callEndFreeDrive(). - Axis constraints allow partial hand-guiding (e.g., only in X/Y plane).
- EndFreeDrive() bool[source]
Exit robot freedrive (hand-guiding) mode.
Restores normal position control mode after freedrive mode was active. Once called, the robot will resume standard motion behavior and will no longer be compliant to manual manipulation.
- Returns:
Trueif the robot successfully exited freedrive mode,Falseif the transition failed.- Return type:
bool
Notes
This method should be called after
FreeDrive()has been used.Motion commands (e.g.,
moveJormoveL) are only permitted once
freedrive mode has been disabled. - Ensure the robot is in a stable pose before exiting freedrive.
- SetTCP(*tcp: ndarray, **kwargs: Any) None[source]
Set the TCP for the robot, i.e. the transformation from the output flange coordinate system to the TCP as a pose.
- Parameters:
tcp (TCPType) – The transformation matrix or pose of the gripper TCP. Default is the identity matrix.
- Return type:
None
- GetTCP(source: str = 'Gripper', out: str = 'T') ndarray[source]
Get the Tool Center Point (TCP) of the robot.
- Parameters:
out (str, optional) – The output format of the gripper TCP. Default is “T” (transformation matrix).
- Returns:
The gripper TCP in the specified output format.
- Return type:
Union[Pose3DType, HomogeneousMatrixType, Vector3DType, RotationMatrixType]
- ZeroFTSensor() None[source]
Zeroes the TCP force/torque measurement from the builtin force/torque sensor by subtracting the current measurement from the subsequent.
- SetLoad(load: load_params | None = None, mass: float | None = None, COM: ndarray | None = None) None[source]
Set the load properties of the robot.
- Parameters:
load (load_params, optional) – The load object to be assigned, by default None.
mass (float, optional) – The mass of the load, by default None.
COM (Vector3DType, optional) – The center of mass of the load, by default None.
- IKin(x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], q0: ndarray, task_space: str | None = None, **kwargs: Any) Tuple[ndarray, int][source]
Compute inverse kinematics to obtain joint positions for a desired pose.
This method computes the inverse kinematic solution using the RTDE interface. The pose is first transformed according to the specified task space, before passing it to the IK solver. The solution closest to the provided joint reference q0 is selected.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType, RotationMatrixType, Vector3DType, QuaternionType, ArrayLike]) – Desired TCP pose. Can be a 4×4 transformation matrix, position/orientation vector (size 6 or 7), or other format supported by x2x.
q0 (JointConfigurationType) – Joint position reference (starting estimate). The solution closest to this is preferred.
task_space (str, optional) – Coordinate system interpretation for x. Supported:
"World","Robot","Object". IfNone, uses the robot’s default task space.**kwargs (dict, optional) – Additional IK solver arguments (such as max_position_error, max_orientation_error), if supported by the RTDE implementation.
- Returns:
JointConfigurationType – Computed joint values (typically of size 6).
int – Status code: -
0→ IK solution valid -1→ IK solution invalid or unstable (popup may have been closed)
- Raises:
ValueError – If task_space is unsupported.
Notes
If no TCP is provided to the RTDE interface, the active TCP is used.
If IK fails (i.e., returned vector length ≠ 6), the method waits briefly,
closes any potential robot popup, and returns status
1. - Returned joint values are not guaranteed to be collision-free or optimal.
- ClosePopup() None[source]
Close an active informational popup on the robot controller.
This method dismisses a non-critical popup dialog on the robot’s teach pendant, such as messages requiring user confirmation. It does not handle safety-related popups.
- Return type:
None
Notes
Use this when non-safety robot messages block program execution.
For safety-related dialogs, use
CloseSafetyPopup()instead.
- CloseSafetyPopup() None[source]
Close a safety-related popup on the robot controller.
This method clears critical safety popups—such as protective stops or safety alerts—that may require operator acknowledgment before motion resumes.
- Return type:
None
Notes
Only call this if you have verified that the robot is in a safe state.
May require additional recovery actions depending on the safety condition.
- class robotblockset.ur.robots_rtde.ur10(robot_name: str = 'ur10', host: str = '192.168.56.101', **kwargs: Any)[source]
Bases:
robot_ur_rtde,ur10_specRTDE-backed wrapper for the Universal Robots UR10 manipulator.
Create a UR10 robot.
- __init__(robot_name: str = 'ur10', host: str = '192.168.56.101', **kwargs: Any) None[source]
Create a UR10 robot.
- Kinmodel(q: ndarray | None = None, tcp: ndarray | None = None, out: str = 'x', internal_kinematics: bool | None = None) Tuple[ndarray, ndarray] | Tuple[ndarray, ndarray, ndarray][source]
Compute the forward kinematics of the robot.
- Parameters:
q (JointConfigurationType, optional) – Joint angles as input to the kinematic model.
tcp (TCPType, optional) – Tool Center Point (TCP) pose or transformation, by default None.
out (str, optional) – Output format for the result (pose, position, etc.), by default “x”.
internal_kinematics (bool, optional) – If None default is used
- Returns:
Pose (or position/rotation) and JacobianType.
- Return type:
tuple
- class robotblockset.ur.robots_rtde.ur10e(robot_name: str = 'ur10e', host: str = '192.168.56.101', **kwargs: Any)[source]
Bases:
robot_ur_rtde,ur10e_specRTDE-backed wrapper for the Universal Robots UR10e manipulator.
Create a UR10e robot.
- __init__(robot_name: str = 'ur10e', host: str = '192.168.56.101', **kwargs: Any) None[source]
Create a UR10e robot.
- Kinmodel(q: ndarray | None = None, tcp: ndarray | None = None, out: str = 'x', internal_kinematics: bool | None = None) Tuple[ndarray, ndarray] | Tuple[ndarray, ndarray, ndarray][source]
Compute the forward kinematics of the robot.
- Parameters:
q (JointConfigurationType, optional) – Joint angles as input to the kinematic model.
tcp (TCPType, optional) – Tool Center Point (TCP) pose or transformation, by default None.
out (str, optional) – Output format for the result (pose, position, etc.), by default “x”.
internal_kinematics (bool, optional) – If None default is used
- Returns:
Pose (or position/rotation) and JacobianType.
- Return type:
tuple
Classes
|
Status and error codes used by the UR RTDE robot interface. |
|
High-level interface for UR robots using the RTDE protocol. |
|
RTDE-backed wrapper for the Universal Robots UR10 manipulator. |
|
RTDE-backed wrapper for the Universal Robots UR10e manipulator. |