Tormach Robot Programming Language
The TRPL is based on Python. All commands interpreted by the TRPL interpreter are Python code, which means you can use any Python code to control the robot. However, the graphical conversational programming utility only supports re-interpretation of a subset of commands as defined here.
Contents
Program structure
A TRPL program is a simple Python file with a single main
function containing the program code. The support RPL commands are imported per default; any additional external libraries can be imported if required.
Note that the program interpreter only can track code execution in the main program file. Blocking commands in external libraries might, therefore, lock up the program execution
The main function is executed in a loop. If you want to break this behavior, use the exit statement.
from robot_command.rpl import * # import all robot commands set_units("mm", "deg") # set the linear and angular unit types for the program # waypoints are defined in the header of the program waypoint_1 = j[0.764, 1.64, 0.741, 0.433, 0.140, 2.74] waypoint_2 = p[361.53,947.19, 937.11, 45, 0, 0] # the main function contains the program code def main(): movel(waypoint_1) # a linear move command sleep(0.5) # wait for 0.5 seconds movej(waypoint_2) # a joint move command sleep(0.5) # wait for 0.5 seconds
Special Python Method Names
The following Python method names have a special meaning in the TRPL interpreter:
-
main: The robot programs main loop. Required in every program.
-
on_abort: Called when the program is aborted as a result of an error or controlled exit by the operator.
-
on_pause: Called when the program is paused.
The on_abort and on_pause methods are useful for disabling digital outputs or cleaning up initialized resources. If an error occurs in the on_pause method on_abort will be called as a fallback. If an error occurs in the on_abort method the program will exit instantly.
Python Stubs
Below you can find Python stub files, supported in most modern IDEs.
To use them, install the robot_command-stubs package by issuing the python3 setup.py install command.
Linear and Angular Units
The TRPL supports multiple linear and angular measurement units. It is advised to define the units used in a program as the first line of the program. Changing units at runtime is supported, but highly discouraged.
Supported linear unit types:
-
“m” - Meters
-
“mm” - Millimeters
-
“in” - Inches
Supported angular unit types:
-
“deg” - Degrees
-
“rad” - Radians
-
robot_command.rpl.
set_units
(linear: str | SharedRegistryObject | None = None, angular: str | SharedRegistryObject | None = None, time: str | SharedRegistryObject | None = None) Sets the active linear, angular and time units for the program.
Parameters: -
linear – Linear/length unit type: m, mm, inch
-
angular – Angular/rotation unit type: deg, rad
-
time – Time unit type: s, min, h
Examples
set_units("mm", "deg", "s") set_units(linear="in") set_units(angular="rad") set_units(time="s")
-
-
robot_command.rpl.
get_units
(with_time: bool = False) -> Tuple[str, str] | Tuple[str, str, str] Returns the active linear, angular and time units from the program.
Parameters: time – return the time unit type when set to True
Returns: Linear/length unit type, angular/rotation unit type and time unit type
Examples
linear, angular = get_units() linear, angular, time = get_units(with_time=True)
Waypoints
Waypoints are defined either as joint configuration, as list of joint positions, or as a robot pose with location in Cartesian coordinates XYZ and orientation in Euler angles ABC. Robot poses furthermore relate to a frame from the world origin, usually located at the robot base. If no frame is active or specified with the waypoint, reference to the world origin is assumed.
Global and Local Waypoints
Global waypoints are waypoints that can be reused between programs. These waypoints are referenced by name inside the TRPL. Contrary, local waypoints are defined in the beginning of a robot program as Python variables.
Joints - Waypoint Defined as Joint Configuration
Joint positions can be defined by using the Joints
object or the JointsFactory
using the j[]
shortcut. The values of j1 to j6 are the six joint positions of the robot arm.
- class
robot_command.rpl.
Joints
(j1: float = 0.0, j2: float = 0.0, j3: float = 0.0, j4: float = 0.0, j5: float = 0.0, j6: float = 0.0) The Joints object consists of six joint position values to be used as target for move commands or to represent the current robot joint state.
Examples
waypoint_1 = Joint(323.62, 345.37, 477.76, 431.10, 918.62) waypoint_2 = Joint(j3=0.543) # all other joint positions are 0.0 by default
-
copy
() -> Joints Creates a copy of the joints object.
Returns: Copy of the joints object.
- static
from_list
(joint_list: List[float]) -> Joints Creates a new joint object from a list of joint positions.
Parameters: joint_list – List of the six joint positions.
Returns: New joints object.
-
from_ros_units
(angular_unit: str | SharedRegistryObject | None = None) Converts the joints object from native ROS units to the target units, removing the unit type if any.
Parameters: angular_unit – Unit type for the angular joint positions.
Returns: The resulting joints object.
-
to_list
() -> List[float] Convert the joints object to a list of joint positions.
Returns: List of the six joint positions.
-
to_ros_units
(angular_unit: str | SharedRegistryObject | None = None) -> Joints Converts the joints object to native ROS units, removing the unit type if any. This is useful if you want to send the resulting data to a ROS service.
Parameters: angular_unit – Unit type for the angular joint positions.
Returns: The resulting joints object.
-
with_units
(angular_unit: str | SharedRegistryObject | None = None) -> Joints Adds a unit type to all positions of the joints object. The defaults are the native ROS units. In case a joint position already has units, the unit type is converted accordingly.
Parameters: angular_unit – Unit type for the angular joint positions.
Returns: The resulting joints object.
-
without_units
(angular_unit: str | SharedRegistryObject | None = None) -> Joints Removes units from the joint positions if any. If no unit type is specified ROS units are assumed.
Parameters: angular_unit – Unit type for the angular joint positions.
Returns: The resulting joints object.
-
- class
robot_command.rpl.
JointsFactory
The JointsFactory class helps constructing Joints object using a shorthand notation. In the robot program it can be accessed using the
j[]
shortcut or thej()
shortcut which supports keyword arguments.Examples
waypoint_1 = j[0.764, 1.64, 0.741, 0.433, 0.140, 2.74] waypoint_2 = j(j3=0.543) # all other joint positions are 0.0 by default
-
robot_command.rpl.
get_joint_values
() -> Joints Returns the current joint values.
Returns: Current joint values.
Examples
joint_value = get_joint_values()
Pose - Waypoint Defined as Pose
Poses can be defined using the Pose
object or the PoseFactory
using the p[]
shortcut. x, y, z are the Cartesian coordinates of the robot position. a, b, c is the orientation defined in Euler angles (static XYZ).
Optionally, poses can be defined with a reference frame defined as frame in the robot UI. When no frame is defined, it is assumed that the waypoint is defined in world coordinates.
User frames are not enforced at runtime. You still need to use a change_user_frame()
statement before an frame becomes active.
- class
robot_command.rpl.
Pose
(x: Number | Quantity = 0.0, y: Number | Quantity = 0.0, z: Number | Quantity = 0.0, a: Number | Quantity = 0.0, b: Number | Quantity = 0.0, c: Number | Quantity = 0.0, frame: str = '', conf: JointConfig | None = None, rev: Number | Quantity | None = None) A robot pose consists of XYZ position ABC orientation parameters.
Optionally, an frame frame can be recorded with a waypoint.
Examples
waypoint_1 = Pose(483.21, 34.21, 21.59, 42.03, 71.14) waypoint_2 = Pose(a=0.543) # all other coordinate values are 0.0 per default.
-
__mul__
(other: Pose) -> Pose Use KDL frame multiplication to apply a frame to a pose.
Parameters: other – Other pose.
Returns: New pose object.
new_wp = Pose(x=10) * waypoint_1 # translates waypoint_1 by x=10 old_wp = Pose(x=10).inverse() * new_wp # translates new_wp back
-
copy
() -> Pose Creates a copy of the pose object.
Returns: A copy of the pose.
- static
from_kdl_frame
(frame: Frame) -> Pose Converts a KDL frame to a pose object.
Parameters: frame – KDL frame.
Returns: New pose object.
- static
from_list
(pose_list: List[float]) -> Pose Creates a new pose object from a list of coordinates.
Parameters: pose_list – List of the six coordinates.
Returns: New pose object.
- static
from_ros_pose
(pose: Pose | PoseStamped) -> Pose Converts a ROS native pose to a pose object.
Parameters: pose – The ROS stamped pose.
Returns: New pose object.
-
from_ros_units
(linear_unit: str | SharedRegistryObject | None = None, angular_unit: str | SharedRegistryObject | None = None) Converts the pose from native ROS units to the target units, removing the unit type.
Parameters: -
linear_unit – Unit type for linear coordinates.
-
angular_unit – Unit type for angular coordinates.
Returns: The resulting pose.
-
-
inverse
() -> Pose Creates the inverse of the pose. Useful for calculating frames.
Returns: New pose object.
-
to_kdl_frame
() -> Frame Converts the pose object to a KDL frame.
Returns: KDL frame.
-
to_list
() -> List[float] Convert the pose to a list of the coordinates. :return: List of the six coordinates.
-
to_ros_pose
() -> Pose Converts the pose object to a native ROS pose.
Returns: ROS pose.
-
to_ros_units
(linear_unit: str | SharedRegistryObject | None = None, angular_unit: str | SharedRegistryObject | None = None) -> Pose Converts the pose to native ROS units, removing the unit type if any. This is useful if you want to send the resulting data to a ROS service.
Parameters: -
linear_unit – Unit type for linear coordinates.
-
angular_unit – Unit type for angular coordinates.
Returns: The resulting pose.
-
-
with_units
(linear_unit: str | SharedRegistryObject | None = None, angular_unit: str | SharedRegistryObject | None = None) -> Pose Adds a unit type to all coordinates of the pose. The defaults are the native ROS units. In case a coordinate already has units, the unit type is converted accordingly.
Parameters: -
linear_unit – Unit type for linear coordinates.
-
angular_unit – Unit type for angular coordinates.
Returns: The resulting pose.
-
-
without_units
(linear_unit: str | SharedRegistryObject | None = None, angular_unit: str | SharedRegistryObject | None = None) -> Pose Removes units from the coordinates if any. If no unit type is specified ROS units are assumed.
Parameters: -
linear_unit – Unit type for linear coordinates.
-
angular_unit – Unit type for angular coordinates.
Returns: The resulting pose.
-
-
- class
robot_command.rpl.
PoseFactory
The PoseFactory class helps constructing Pose object using a shorthand notation. In the robot program it can be accessed using the
p[]
shortcut or thep()
shortcut which supports keyword arguments.Examples
waypoint_1 = p[202.73, 750.08, 91.75, 6.63, 53.21, "table"] # captured with table user frame waypoint_2 = p(y=10.0, frame="table") # all other coordinate values are 0.0 per default.
-
robot_command.rpl.
get_pose
(apply_user_frame: bool = True, apply_tool_frame: bool = True) -> Pose Returns the current robot pose.
Parameters: -
apply_user_frame – Applies the active user frame to the world pose.
-
apply_tool_frame – Applies the active tool frame to the world pose.
Returns: Current robot pose.
Examples
current_pose = get_pose()
-
-
robot_command.rpl.
to_local_pose
(global_pose, apply_work_offset: bool = True, apply_tool_offset: bool = True) -> Pose Converts a global pose to a local pose
Parameters: -
global_pose – Global workspace Pose to convert to local coordinates (based on specified arguments)
-
apply_work_offset – Applies the active work offset
-
apply_tool_offset – Applies the active tool offset
Returns: converted local pose
Examples
local_pose = to_local_pose(global_pose) work_only_pose = to_local_pose(global_pose, apply_tool_offset=False)
-
Setting and getting global waypoints from robot programs
Robot programs can set or get a global waypoint as part of its execution. Setting of a new global waypoint is achieved by calling robot_command.rpl.set_global_waypoint()
. Getting of existing global waypoints is accomplished by calling robot_command.rpl.get_global_waypoint()
.
-
robot_command.rpl.
set_global_waypoint
alias of
funct
-
robot_command.rpl.
get_global_waypoint
alias of
funct
Movement
The robot can be moved using the following move types:
movej - Joint Move
-
robot_command.rpl.
movej
(target: Pose | Joints, v: float = None, probe: int = 0, velocity_scale: float = 1.0) -> Tuple[int, Time, Joints, Pose] | None Moves the robot end effector to the target waypoint with a joints move. Targets can be local waypoints or global waypoints defined as pose or joints.
Parameters: -
target – target waypoint or joints target
-
velocity_scale – scale factor for velocity (default is full speed)
-
probe – specify the probe mode (2-6, or 0 for no probing) Probe mode 2: look for rising edge on probe signal (i.e. contact), raise ProbeFailedError if move completes without seeing a rising edge Probe mode 3: like mode 2 but does not raise error if move completes without rising edge Probe mode 4: like mode 2 but looks for falling edge Probe mode 5: like mode 4 but does not raise an error if move completes without falling edge Probe mode 6: “retract” mode, ignore falling edges and allow motion while probe signal is active, but raise ProbeUnexpectedContactError if a rising edge is seen
-
v –
scale factor for velocity (default is full speed)
Deprecated since version 3.1.1: use velocity_scale instead
Returns: tuple of probe results (for probing mode 2,3,4,5) or None: (probe contact type (0 = no contact, 1 = rising, 2 = falling), time of probe contact, Joint positions at probe contact, End-effector position / orientation pose at probe contact)
Examples
movej(waypoint_1) movej("global_waypoint_1", velocity_scale=0.6) movej(p[0, 100, 0, 90, 20, 0])
-
movel - Linear Move
-
robot_command.rpl.
movel
(target: Pose | Joints, a: float = None, v: float = None, probe: int = 0, velocity: float | Quantity | None = None, accel: float | Quantity | None = None, accel_scale: float = 0.5, duration: float | Quantity | None = None, strict_limits: bool = False) -> Tuple[int, Time, Joints, Pose] | None Moves the robot end effector in a straight line from the current position to the target waypoint. Targets can be local waypoints or global waypoints defined as pose or joints.
Parameters: -
target – target waypoint
-
probe – specify the probe mode (2-6, or 0 for no probing) Probe mode 2: look for rising edge on probe signal (i.e. contact), raise ProbeFailedError if move completes without seeing a rising edge Probe mode 3: like mode 2 but does not raise error if move completes without rising edge Probe mode 4: like mode 2 but looks for falling edge Probe mode 5: like mode 4 but does not raise an error if move completes without falling edge Probe mode 6: “retract” mode, ignore falling edges and allow motion while probe signal is active, but raise ProbeUnexpectedContactError if a rising edge is seen
-
velocity – move velocity as absolute value, interpreted in terms of currently set machine units if quantity without units is given.
-
accel – move acceleration as absolute value, interpreted in terms of currently set machine units if quantity without units is given.
-
accel_scale – move acceleration scaling factor 0.0 - 1.0
-
duration – target move duration in seconds. If move duration based on other inputs is longer, the planned duration will be used.
-
strict_limits – Enforces strict limits. Moves violating the velocity and acceleration limits will error.
-
v –
move velocity scaling factor 0.0 - 1.0
Deprecated since version 3.1.1: use velocity instead
-
a –
move acceleration scaling factor 0.0 - 1.0
Deprecated since version 3.1.1: use accel_scale instead
Returns: tuple of probe results: (probe contact type (0 = no contact, 1 = rising, 2 = falling), time of probe contact, Joint positions at probe contact, End-effector position / orientation pose at probe contact)
Examples
movel(waypoint_1) movel("global_waypoint_1", velocity=100) movel(j[0.764, 1.64, 0.741, 0.433, 0.140, 2.74])
-
movec - Circular Move
-
robot_command.rpl.
movec
(interim: Pose | Joints, target: Pose | Joints, a: float = None, v: float = None, probe: int = 0, velocity: float | Quantity | None = None, accel: float | Quantity | None = None, accel_scale: float = 0.5, duration: float | Quantity | None = None, strict_limits: bool = False) -> Tuple[int, Time, Joints, Pose] | None Circular/Arc move command.
Parameters: -
interim – interim waypoint
-
target – target waypoint
-
probe – specify the probe mode (2-6, or 0 for no probing) Probe mode 2: look for rising edge on probe signal (i.e. contact), raise ProbeFailedError if move completes without seeing a rising edge Probe mode 3: like mode 2 but does not raise error if move completes without rising edge Probe mode 4: like mode 2 but looks for falling edge Probe mode 5: like mode 4 but does not raise an error if move completes without falling edge Probe mode 6: “retract” mode, ignore falling edges and allow motion while probe signal is active, but raise ProbeUnexpectedContactError if a rising edge is seen
-
velocity – move velocity as absolute value, interpreted in terms of currently set machine units if quantity without units is given.
-
accel – move acceleration as absolute value, interpreted in terms of currently set machine units if quantity without units is given.
-
accel_scale – move acceleration scaling factor 0.0 - 1.0
-
duration – target move duration in seconds. If move duration based on other inputs is longer, the planned duration will be used.
-
strict_limits – Enforces strict limits. Moves violating the velocity and acceleration limits will error.
-
v –
move velocity scaling factor 0.0 - 1.0
Deprecated since version 3.1.1: use velocity instead
-
a –
move acceleration scaling factor 0.0 - 1.0
Deprecated since version 3.1.1: use accel_scale instead
Returns: tuple of probe results (for probing mode 2,3,4,5) or None: (probe contact type (0 = no contact, 1 = rising, 2 = falling), time of probe contact, Joint positions at probe contact, End-effector position / orientation pose at probe contact)
Examples
movec(waypoint_1, waypoint_2)
-
movef - Free-form Move
-
robot_command.rpl.
movef
(target: Pose | Joints) -> None Free move command.
Parameters: target – target target
Trajectory Execution
In same cases it is beneficial to execute a raw trajectory pre-planned in another program, for example Maya Mimic. The robot program supports loading, saving and executing such trajectories.
-
robot_command.rpl.
load_trajectory
(file_path: str) -> JointTrajectory Loads a raw joint trajectory from a CSV file and returns them in ROS format.
Parameters: file_path – Path of the CSV file.
Returns: A ROS joint trajectory.
-
robot_command.rpl.
save_trajectory
(file_path: str, trajectory: JointTrajectory) -> None The save trajectory command saves a joint trajectory to a CSV file.
Parameters: -
file_path – Path of the CSV file.
-
trajectory – The joint trajectory to save.
-
-
robot_command.rpl.
execute_trajectory
(trajectory: JointTrajectory, v: float = None, retime: bool = False, velocity_scale: float = 1.0) -> None The execute trajectory command executes a ROS JointTrajectory. Before running the joint trajectory, the robot moves to the start joint position using a joint move command. :param velocity_scale: move velocity scaling factor 0.0 - 1.0 :param trajectory: a ROS joint trajectory :param retime: Enable retiming the trajectory to make use of the velocity scaling.
Parameters: v –
move velocity scaling factor 0.0 - 1.0
Deprecated since version 3.1.1: use velocity_scale instead
Examples
trajectory = load_trajectory('test.csv') execute_trajectory(trajectory) save_trajectory('test2.csv', trajectory)
Glossary of Move Errors
Move commands typically fails due to two major reasons, either during planning or during execution. You can catch those errors and retry a move inside the robot program.
- exception
robot_command.rpl.
MovePlanningError
- exception
robot_command.rpl.
MoveExecutionError
(message=None, error_code=None)
Examples
try: movel(waypoint) except MovePlanningError: # is raised in case of a planning error notify("Move planning failed", warning=True)
Path Blending
Joint moves as well as linear and circular moves can be blended together into one continuous motion. This behavior can be enabled using the set_path_blending()
method. Note that the motion will be executed before the next non-motion command. To force the execution of blended commands, use the the sync()
method.
-
robot_command.rpl.
set_path_blending
(enable: bool, blend_radius: float | None = None) -> None Enables or disables path blending and sets the blend radius.
Parameters: -
enable – Enable or disable path blending.
-
blend_radius – The blend radius between moves in meters.
Examples
set_path_blending(True, 0.0) # enable path blending, blend radius 0.0m movej(waypoint1) movej(waypoint2) movej(waypoint3) sync() # moves executed before this command set_path_blending(False) # disable path blending again
-
-
robot_command.rpl.
sync
() -> None The sync command is used in wait cycles and to force the execution of queued move commands.
User and Tool Frames
The TRPL supports an arbitrary number of named user and tool frames. These frames are usually defined in the robot UI, however, can also be set inside a program.
User Frames
-
robot_command.rpl.
change_user_frame
(name: str | None) -> None Change the currently active user frame. If an empty string or
None
is used as the name parameter, the empty user frame world becomes active.Parameters: name – The name of the tool frame to activate or None to disable user frames.
Examples
change_user_frame("table") change_user_frame(None) # disable any active frames
-
robot_command.rpl.
set_user_frame
(name: str, pose: Pose | str | None = None, position: Pose | str | None = None, orientation: Pose | str | None = None) -> None Sets a user frame using a pose, position or orientation or clears an frame.
The position and orientation arguments can be combined to overwrite the pose’s position or orientation.
Parameters: -
name – Name of the user frame
-
pose – Pose to use for the user frame
-
position – Use the position of this pose to override the position of the pose.
-
orientation – Use the orientation of this pose to override the orientation of the pose.
Examples
set_user_frame("table", p[0, 100, 0, 0, 0, 0]) set_user_frame("frame_1", waypoint_2, orientation=Pose(a=90)) set_user_frame("frame_1") # clears frame_1
-
-
robot_command.rpl.
get_user_frame
(name: str) -> Pose | None Returns the pose of a user frame.
Parameters: name – Name of the user frame.
Returns: Pose of the user frame.
Raises: TypeError – if no user frame with the name is found
Examples
pose = get_user_frame("table")
-
robot_command.rpl.
user_frame
(pose=None, position=None, orientation=None, world=False) Scoped frame command. Applies a user frame temporarily on top of the currently active user frame.
The scoped frame command can be used to automatically switch the active frame back to a previous state when the scope is left. Scoped frames can be nested. Scoped frames are temporary and do not have a name.
Parameters: -
pose – The frame pose.
-
position – A pose from which the position is used for the frame.
-
orientation – A pose from which the orientation is used for the frame.
-
world – If set to True the frame is absolute.
Examples
with user_frame(p[0, 100, 0, 90, 20, 0]): # creates a temporary frame and activates it movel(Pose(x=10)) # move x by 10 starting from the frame # the active frame automatically reset when the scope is left
-
-
robot_command.rpl.
get_active_user_frame
() -> str Returns the name of the active user frame.
Examples
active_user_frame_name = get_active_user_frame()
Tool Frames
-
robot_command.rpl.
change_tool_frame
(name: str | None) -> None Change the currently active tool frame. If an empty string or
None
is used as the name parameter, the empty tool frame none becomes active.Parameters: name – The name of the tool frame to activate or None to disable tool frames.
Examples
change_tool_frame("table") change_tool_frame(None) # disable any active frames
-
robot_command.rpl.
set_tool_frame
(name: str, pose: Pose | str = None, position: Pose | str = None, orientation: Pose | str = None) -> None Sets a tool frame using a pose, position or orientation or clears an frame.
The position and orientation arguments can be combined to overwrite the pose’s position or orientation.
Parameters: -
name – Name of the tool frame
-
pose – Pose to use for the tool frame
-
position – Use the position of this pose to override the position of the pose.
-
orientation – Use the orientation of this pose to override the orientation of the pose.
Examples
set_tool_frame("some_tool", p[0, 0, 100, 0, 0, 0]) set_tool_frame("other_tool", waypoint_2, position=Pose(z=0.1)) set_tool_frame("other_tool") # clears frame other_tool
-
-
robot_command.rpl.
get_tool_frame
(name: str) -> Pose | None Returns the pose of a tool frame.
Parameters: name – Name of the tool frame.
Returns: Pose of the user frame or None if it does not exist.
Raises: TypeError – if no tool frame with the name is found
Examples
pose = get_tool_frame("tool1")
-
robot_command.rpl.
get_active_tool_frame
() -> str Returns the name of the active tool frame.
Examples
active_tool_frame_name = get_active_tool_frame()
Digital I/O
Digital input/output pins can be accessed via their name or by their number.
-
robot_command.rpl.
set_digital_out
(nr_or_name: int | str, state: bool) -> None Sets a digital output pin to high or low state.
Parameters: -
nr_or_name – The number or name of the digital output pin.
-
state – Set to True or False for on and off.
Examples
set_digital_out("gripper", True) set_digital_out(2, False)
-
-
robot_command.rpl.
get_digital_in
(nr_or_name: str | int) -> bool Returns the current digital input state.
Parameters: nr_or_name – The number or name of the digital output pin.
Returns: True or False for High and Low.
Examples
io_state = get_digital_in("gripper") x = get_digital_in(3)
PathPilot Remote
The PathPilot remote interface can be used to remotely control a PathPilot instance.
-
robot_command.rpl.
pathpilot_cycle_start
(instance: str = '') -> None Starts a cycle on the remote PathPilot instance. If no instance argument is given, the command is executed on the first connected PathPilot instance.
Parameters: instance – PathPilot instance on which cycle start should be executed.
Examples
pathpilot_cycle_start() pathpilot_cycle_start("left_mill")
-
robot_command.rpl.
pathpilot_mdi
(command: str, instance: str = '') -> None Starts an MDI command on the remote PathPilot instance. If no instance argument is given, the command is executed on the first connected PathPilot instance.
Parameters: -
command – MDI command to execute.
-
instance – PathPilot instance on which this command shall be executed.
Examples
pathpilot_mdi("G0 X10") pathpilot_mdi("G1 Y-5 F300", "right_mill")
-
-
robot_command.rpl.
get_pathpilot_state
(instance: str = '') -> str Returns the current state of a PathPilot instance. If no instance argument is given, the command is executed on the first connected PathPilot instance.
Possible states are:
-
“disconnected” - Instance disconnected
-
“estop” - Emergency stop active
-
“running” - a program is running
-
“ready” - instance is ready to start program
-
“idle” - instance is idle, no program loaded
Parameters: instance – PathPilot instance on which cycle start should be executed.
Returns: The current PathPilot state.
Examples
state = get_pathpilot_instance() while get_pathpilot_instance("left_mill") != "ready": sleep(0.1)
-
-
robot_command.rpl.
set_machine_frame
(pose: Pose | str, instance: str = '') -> None Sets the origin frame for the 3D visualization of the PathPilot remote machine model.
Parameters: -
pose – Pose to use for the machine frame.
-
instance – Optional machine instance name. If not given, default instance is used.
Examples
set_machine_frame(p[0,0,0,90,0,0], "instance") set_machine_frame(Pose(x=100)) # sets frame for default instance
-
Notifications
The TRPL supports interactive user notifications displayed in the robot UI.
-
robot_command.rpl.
notify
(message: str, warning: bool = False, error: bool = False, image_path: str = '', timeout: float | None = None) -> None Creates a popup notification message on the robot UI.
The
message
argument text is shown to the user.By default, the message is displayed as informational and thus will not block the program flow. The
warning
argument shows a warning message, which breaks program flow and can be declined by the operator. Theerror
argument shows a blocking error message, which aborts the program.The optional
image_path
argument can be used to display an informational image along with the messageParameters: -
message – Message text to display in the popup.
-
warning – Set to true if this message is a warning.
-
error – Set to true if this message is an error message.
-
image_path – Optional path to an image file to displayed in the popup.
-
timeout – Optional timeout in seconds.
Examples
notify("Hello World!") notify("No part found, check the palette.", warning=True) notify("This should not happen.", error=True, image_path="./fatal_error.png")
-
-
robot_command.rpl.
input
(message: str, default: str = '', image_path: str = '') -> float Creates a popup input dialog on the robot UI.
The
message
argument text is shown to the user.The
option
default argument can be used to set the default input text.The optional
image_path
argument can be used to display an informational image along with the message.Parameters: -
message – Message text to display in the popup.
-
default – The default input value.
-
image_path – Optional path to an image file to displayed in the popup.
Returns: User input text or None if cancelled
Examples
user_input = input("How many parts should be made?", default="5") n = int(user_input)
-
Program Flow
-
robot_command.rpl.
sleep
(secs: float) -> None The sleep command pauses the program execution for
t
seconds.Parameters: secs – sleep time in seconds
Examples
sleep(5.0)
-
robot_command.rpl.
pause
(optional: bool = False, active: bool = False) -> None The pause command pauses the program execution. Equivalent to M01 break.
The
optional
states whether the pause is optional or not. Optional pause can be enabled in the robot UI by the operator.Parameters: -
optional – If this pause is optional or not.
-
active – When set to true, this indicates an active pause allowing to operator to jog the program.
Examples
pause() pause(optional=True)
-
-
exit
() The Python builtin
exit
command instantly aborts the program execution.Examples
exit()
Loops
The TRPL supports all Python statements, including loops.
Examples
# move through 4 points for i range(5): movel(Pose(x=i*0.1)) # wait for a condition while get_digital_in("start") == False: sync()
Conditions
Similarly, conditions are also supported.
Examples
if get_pathpilot_state() != "ready": notify("PathPilot is not ready", warning=True)
Subprograms
The TRPL supports subprograms / reusable Python functions.
Examples
def subprogram(): movel(p[0, 100, 0, 0, 0, 0]) def main(): subprogram()
Persistent Parameter Storage
The TRPL supports storing and retrieving Python objects to the persistent parameter store. This is useful if you want to store data between program runs.
-
robot_command.rpl.
set_param
(name: str, value: object) -> None Sets a user parameter to a the defined value.
Parameters: -
name – Parameter name.
-
value – Value to store.
set_param("my_waypoint", waypoint1)
-
-
robot_command.rpl.
get_param
(name: str, default: object = None) -> object Fetch a stored user parameter.
Parameters: -
name – Parameter name.
-
default – Default value return if the parameter is not defined.
Returns: Returns a base Python type, construct rpl types or returns a dict if the parameter is set, else returns the default value.
Examples
wp = get_param("my_waypoint", Pose())
-
-
robot_command.rpl.
delete_param
(name: str) -> None Removes a user parameter
Parameters: name – Parameter name to delete
delete_param("my_waypoint")
Probing
Under development
The probel
command is a simple probing cycle:
-
robot_command.rpl.
probel
(target: Pose | Joints | str, a: float = 0.5, v: float = 0.1, v_retract: float = 0.1, away: bool = False, check_retract_contact: bool = False) -> Pose Simple probing cycle that returns to the initial pose (regardless of the probe result). The sequence is:
-
Linear move at specified vel / accel scale towards the target position
-
Stop at probe contact, error condition, or motion end
-
Retract to original position
-
Raise any errors from the cycle, or return the probe result
Parameters: -
target – end point of probing motion (probe cycle uses movel internally)
-
v – move velocity scaling factor 0.0 - 1.0
-
a – move acceleration scaling factor 0.0 - 1.0
-
v_retract – velocity scaling factor to use during retract phase
-
away – Probe towards work (default) if False, otherwise probe away from work
-
check_retract_contact – Optionally check for contacts during retract move (to avoid retracting into an obstacle and breaking a probe tip)
assumes mode 2/4 for probing, meaning an error will be thrown if it reaches the end without contact. Caller can catch this exception if they want mode 3/5 functionality
Examples
contact_pose = probel(probe_goal_pose, a=0.5, v=0.01, v_retract=0.1, away=False, check_retract_contact=False)
-
When called, probel()
executes two motions:
movel()
towards a target position at specified accelerations scale a (default 0.5), and velocity scale v (default 0.01), stopping when the probe makes contact.
movel()
to retract to the original position (at velocity v_retract, default 0.1)
It’s also possible to create custom probing cycles by adding a “probe” keyword to any of the following move commands:
For example, a linear move that expects probe contact would look like this:
contact_type, contact_time, contact_joint_positions, contact_pose = movel(probe_goal_pose, probe=2)
The numerical value of the “probe” argument has the following meaning:
probe=2 means look for contact (rising edge), or raise a ProbeFailedError
if it reaches the end without making contact, or if the probe is active at the start of the move.
probe=3 is like (2), but reaching the end of the motion is not an error.
probe=4 means look for the probe to break contact (falling edge). It raises a ProbeFailedError
if it reaches the end without breaking contact, or if the probe is not active at the start.
probe=5 is like (4), but reaching the end of the motion is not an error.
probe=6 is for retraction. The motion will execute normally with the probe on or off, but if the probe signal gets a rising edge (i.e. retracting from a surface too far and hitting another surface), then it will raise a ProbeUnexpectedContactError
if the probe fails to make contact in mode 3 (or leave contact in mode 5), movel will return “None” instead of a result tuple.
Glossary of Probe Errors
There are several probing-specific errors that are reported as python exceptions. All of them are derived from the ProbeError
exception class.
- exception
robot_command.rpl.
ProbeUnexpectedContactError
(error_code=None)
- exception
robot_command.rpl.
ProbeContactAtStartError
(error_code=None)
- exception
robot_command.rpl.
ProbeFailedError
(error_code=None)
Interrupts
The TRPL supports interrupts from external sources. This is useful for example to abort a program when a button connected to a digital input pin is pressed or to react to a message received from a ROS topic.
- class
robot_command.rpl.
InterruptSource
(value) Interrupt source type.
DigitalInput: React to a change on a digital input pin.
UserIo: React to a change on a user IO pin. (triggered by HAL)
Program: React to a program interrupt. (e.g. a ROS topic)
-
robot_command.rpl.
register_interrupt
(source: InterruptSource, nr_or_name: int | str, fct: Callable) -> None Registers a interrupt function to an interrupt source.
Parameters: -
source – The interrupt source type.
-
nr_or_name – Number or name of the interrupt source, e.g. 1 for Digital Input 1.
-
fct – The function which should be called when the interrupt is triggered, if None is passed, this unregisters and disables the interrupt.
Examples
def interrupt_handler(value): if value: exit() # exit program when digital input 1 is high register_interrupt(InterruptSource.DigitalInput, 1, interrupt_handler)
-
-
robot_command.rpl.
trigger_interrupt
(nr: int, value: Any) -> None Triggers a program interrupt.
Parameters: -
nr – Program interrupt number which should be triggered.
-
value – Value which is passed along with the triggered interrupt.
Examples
trigger_interrupt(2, 342.34)
-
Calibration
The robot_command.calibration
module contains a few useful functions to write custom calibration programs. Note that these functions must be imported manually.
-
robot_command.calibration.
calculate_tool_frame_4
(wp1: Pose, wp2: Pose, wp3: Pose, wp4: Pose) -> Pose Calculate the XYZ coordinates of the tool frame using 4 waypoints using the center of sphere method.
Parameters: -
wp1 – Waypoint 1
-
wp2 – Waypoint 2
-
wp3 – Waypoint 3
-
wp4 – Waypoint 4
Returns: The tool frame pose containing the XYZ tool frame.
-
-
robot_command.calibration.
calculate_user_frame_3
(origin_wp: Pose, x_axis_wp: Pose, y_axis_wp: Pose) -> Pose Calculates the user frame origin pose based on 3 waypoints that lie on a plane.
The angular unit of all input poses must be in radians.
Parameters: -
origin_wp – Origin of the plane.
-
x_axis_wp – A waypoint that lies on the X-axis of the plane.
-
y_axis_wp – A waypoint that lies in the direction of the Y-axis of the plane.
Returns: Origin waypoint of the constructed user frame.
-
-
robot_command.calibration.
calculate_user_frame_4
(origin_wp: Pose, x_axis_wp: Pose, y_axis_wp: Pose, position_wp: Pose) -> Pose Calculates the user frame origin pose based on 3 waypoints that lie on a plane and one additional waypoint which is used to define the origin location.
The angular unit of all input poses must be in radians.
Parameters: -
origin_wp – Origin of the plane.
-
x_axis_wp – A waypoint that lies on the X-axis of the plane.
-
y_axis_wp – A waypoint that lies in the direction of the Y-axis of the plane.
-
position_wp – Origin location of the new user frame.
Returns: Origin waypoint of the constructed user frame.
-
List of Supported and Deprecated Commands
New in version 0.1.3.
New in version 0.1.4.
New in version 0.2.2.
New in version 3.0.0.
New in version 3.0.2.
New in version 3.0.5.
New in version 3.1.1.
Deprecated since version 3.0.2.
-
set_work_offset()
-
set_tool_offset()
-
get_work_offset()
-
get_tool_offset()
-
change_work_offset()
-
change_tool_offset()
-
set_machine_offset()
-
work_offset()