Python

Geometry

class Config

Type alias for List[float] as a joint configuration of a robot.

class Frame

Represents a transformation or pose in 3D Cartesian space.

__init__(*, x: float, y: float, z: float, a: float, b: float, c: float, qw: float, qx: float, qy: float, qz: float)

Create a frame by keyworld-only arguments. Note that only either Euler angles (a, b, c) or Quaternions (qw, qx, qy, qz) are allowed.

static Identity() Frame
static from_matrix(data: List[float]) Frame
static from_translation(x: float, y: float, z: float) Frame
static from_quaternion(x: float, y: float, z: float, qw: float, qx: float, qy: float, qz: float) Frame
static from_euler(x: float, y: float, z: float, a: float, b: float, c: float) Frame

The angles a, b, c are using the extrinsic XYZ convention.

property translation: List[float]

Cartesian position [x, y, z] of the frame.

property matrix: List[float]

Flattened 4x4 matrix representation of the frame.

property euler: List[float]

The angles a, b, c are using the extrinsic XYZ convention.

property quaternion: List[float]

The rotation as a list [w, x, y, z] of the quaternion.

inverse() Frame

Calculate the inverse transformation of the frame.

translational_distance(other: Frame) float

Calculates the Euclidian norm of the position difference.

angular_distance(other: Frame) float

Calculates the angle of the rotational difference.

interpolate(t: float, other: Frame) Frame

Calculates a spherical linear interpolation between this and the other frame at the interpolation parameter t.

class Twist

Represents a velocity in 3D Cartesian space.

Element

class Element

The base element of a scene.

name: str

The unique name of the element, for display and identification.

tags: list[str]

Given tags of the element, might be with a parameter param=value.

has_tag(tag: str) bool

Checks whether a tag is present on the element.

get_parameter(tag: str) str | None

Reads the value of a tag parameter param=value.

Waypoints

Waypoint: Element

A joint-space waypoint with possible position, velocity, and/or acceleration values.

position: Config

The joint position at the waypoint.

velocity: Config

The joint velocity at the waypoint.

acceleration: Config

The joint acceleration at the waypoint.

__init__(position: Config)

Construct a waypoint with given position and zero velocity and acceleration.

__init__(position: Config, velocity: Config)

Construct a waypoint with given position and velocity and zero acceleration.

__init__(position: Config, velocity: Config, acceleration: Config)

Construct a waypoint with given position, velocity, and acceleration.

CartesianWaypoint: Element

A Cartesian-space waypoint with possible position, velocity, and/or acceleration values.

position: Frame

Frame of the position.

velocity: Frame

Frame of the velocity.

acceleration: Frame

Frame of the acceleration.

reference_config: Config | None

An optional joint position that is used as a reference for inverse kinematics.

__init__(position: Frame, reference_config: Config = None)

Construct a Cartesian waypoint with given position and zero velocity and acceleration.

__init__(position: Frame, velocity: Frame, reference_config: Config = None)

Construct a Cartesian waypoint with given position and velocity and zero acceleration.

__init__(position: Frame, velocity: Frame, acceleration: Frame, reference_config: Config = None)

Construct a Cartesian waypoint with given position, velocity, and acceleration.

Region: Element

A joint-space region with possible position, velocity, and/or acceleration values.

min_position: Config
max_position: Config
min_velocity: Config
max_velocity: Config
min_acceleration: Config
max_acceleration: Config
class CartesianRegionBound

The min or max boundary of a Cartesian region.

x: float

Translation along x-axis.

y: float

Translation along y-axis.

z: float

Translation along z-axis.

gamma: float

Euler angle around the global z-axis.

alpha: float

Angle from the global z-axis.

CartesianRegion: Element

A Cartesian-space region with possible minimum and maximum position, velocity, and/or acceleration values.

min_position: CartesianRegionBound
max_position: CartesianRegionBound
min_velocity: CartesianRegionBound
max_velocity: CartesianRegionBound
min_acceleration: CartesianRegionBound
max_acceleration: CartesianRegionBound
reference_config: Config | None

An optional joint position that is used as a reference for inverse kinematics.

class MultiRobotPoint

Type alias for Dict[Robot, Config | Waypoint | CartesianWaypoint]. A type for specifying an exact start or goal point per robot.

class Point

Type alias for Config | Waypoint | CartesianWaypoint | MultiRobotPoint | Region | CartesianRegion. All types for specifying motion start or goals, either exact or by region.

class ExactPoint

Type alias for Config | Waypoint | CartesianWaypoint | MultiRobotPoint. All types for specifying exact start or goal points.

Obstacles

class Box

A box collision object.

x: float

Width of the box.

y: float

Depth of the box.

z: float

Height of the box.

__init__(x: float, y: float, z: float)

Construct a box of size x, y, z along the respective axis, corresponding to the width, depth, height of the box.

class Capsule

A capsule collision object.

radius: float

Radius of the capsule.

length: float

Length of the capsule.

__init__(radius: float, length: float)

Construct a capsule with the given radius and length. As a side note, a capsule is computationally efficient for collision checking.

class Convex

A convex mesh collision object.

file_path: Path | None

The file path of the mesh object when loaded from a file.

property bounding_box_minimum: List[float]

The minimum position of the axis-aligned bounding box.

property bounding_box_maximum: List[float]

The maximum position of the axis-aligned bounding box.

load_from_file(path: Path, scale: float = None)

Loads a mesh from a *.obj or *.stl file from the given path, and returns the convex hull of the mesh. If no scale is given, we automatically estimate the scale of the mesh to match base SI units e.g. [m].

reference_studio_file(path: Path, scale: float = None)

Create a reference to a mesh file with the given filename already uploaded to a Studio project. This is helpful to visualize objects dynamically using Studio Live.

class Cylinder

A cylinder collision object.

radius: float

Radius of the cylinder.

length: float

Length of the cylinder.

__init__(radius: float, length: float)

Construct a cylinder with the given radius and length.

class HeightField

A height field or depth map collision object.

class Matrix

Type alias for List[List[float]].

x: float

Size along the x-axis.

y: float

Size along the y-axis.

height: Matrix

Matrix containing the heights at evenly spaced grid points. The collision object will interpolate linearly between the heights, and will create a volume to zero height.

__init__(x: float, y: float, heights: Matrix)

Construct a height field with the given data.

class Sphere

A sphere collision object.

radius: float

Radius of the sphere.

__init__(radius: float)

Construct a sphere with the given radius.

Obstacle: Element

An environment obstacle.

class Object

Type alias for Box | Capsule | Convex | Cylinder | HeightField | Sphere.

name: str

The name of the obstacle.

color: str

The hex-string representation of the obstacle’s color, without the leading #.

collision: Object

The object for collision checking.

origin: Frame

The pose of the object.

for_visual: bool = True

Whether this obstacle is used for visual checking.

for_collision: bool = True

Whether this obstacle is used for collision checking.

safety_margin: float = 0.0

An additional obstacle-specific safety margin. Currently, only positive values are supported. Setting a value of -infinity disables the collision check completely.

Obstacle(object: Object, origin: Frame = Frame.Identity(), color: str = '000000')
Obstacle(name: str, object: Object, origin: Frame = Frame.Identity(), color: str = '000000')

Environment

class Environment
safety_margin: float

Additional global safety margin used for collision checking.

__init__(robot: Robot, safety_margin=0.0)

Constructs a new environment with the given robot, and a global safety margin for collision checking.

get_robot(name: str = '') Robot

Get the robot with the given name from the environment. In case there is only a single robot in the environment, the default empty name argument will return this robot. Otherwise throws an error if no robot with the name exists.

get_waypoint(name: str) Point

Get the waypoint with the given name from the environment. Returns either a Waypoint, a CartesianWaypoint, a Region, or a CartesianRegion. Throws an error if no waypoint with the name exists.

get_waypoint_by_tag(tag: str) Point

Get a waypoint within the environment given a tag. If multiple waypoints have the same tag, the first one to be found is returned. Tags are case-insensitive.

get_obstacle(name: str) Obstacle

Get the obstacle with the given name from the environment. Throws an error if no obstacle with the name exists.

get_obstacles_by_tag(tag: str) list[Obstacle]

Get all obstacles within the environment that carry the given tag. Tags are case-insensitive.

add_obstacle(obstacle: Obstacle) Obstacle

Adds an obstacle to the environment. Returns a pointer to the added obstacle for future changes.

add_obstacle(object: Object, origin=Frame.Identity()) Obstacle

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

add_obstacle(name: str, object: Object, origin=Frame.Identity(), color='000000') Obstacle

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

remove_obstacle(obstacle: Obstacle)

Removes the given obstacles from the environment and from all collision checking.

update_fixed_obstacles()

Updates all fixed obstacles for the internal collision checking. This should be called after changing e.g. the position or size of an obstacle.

update_height_field(obstacle: Obstacle)

Updates the heights matrix of a given height field obstacle for the internal collision checking.

update_joint_position(robot: Robot, joint_position: Config)

Updates the joint position of the given robot for the internal collision checking.

check_collision(joint_position: Config) bool

Returns whether the given joint position is in collision with the environment (considering the security margin).

check_collision(robot: Robot, joint_position: Config) bool

Returns whether the given joint position for the specific robot is in collision with the environment (considering the security margin).

get_collision_free_joint_position_nearby(joint_position: Config, robot: Robot = None) Config | None

Calculate a collision free joint position close to the reference position.

Robots

class Robot
model: str

The model name of the robot.

name: str

The unique name of the robot in the project.

set_base(base: Frame)

Sets the origin of the robot’s base.

set_speed(speed: float)

Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.

class RobotArm(Robot)
degrees_of_freedom: int

The number of joints of the robot.

min_position: Config

Minimum position for each joint. [rad]

max_position: Config

Maximum position for each joint. [rad]

max_velocity: Config

Maximum absolute velocity for each joint. [rad/s]

max_acceleration: Config

Maximum absolute acceleration for each joint. [rad/s^2]

max_jerk: Config

Maximum absolute jerk for each joint. [rad/s^3]

The obstacles for each robot link.

end_effector_obstacle: Obstacle | None

An (optional) obstacle attached to the robot’s flange.

item_obstacle: Obstacle | None

An (optional) obstacle attached to the robot’s TCP. The obstacle’s frame is defined relative to the TCP frame.

property base: Frame

The origin of the robot’s base.

property flange_to_tcp: Frame

The transformation from the robot’s flange to the robot’s TCP, e.g. for using inverse kinematics or an item obstacle.

set_speed(speed: float)

Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.

calculate_tcp(joint_position: Config) Frame

Calculates the forward_kinematics and returns the frame of the robot’s TCP.

calculate_tcp_speed(joint_position: Config, joint_velocity: Config) float

Calculates the forward_kinematics and returns the norm of the Cartesian velocity of the robot’s TCP.

inverse_kinematics(tcp: Frame, reference_config: Config = None) Config

Finds a joint position so that the robot’s TCP is at the given frame, which is defined in the world coordinate system. In general, the solution will try to stay close to the reference_config parameter.

We use a numerical optimization for robots with more than 6 degrees of freedom. Then, the reference configuration is used as a starting point for the optimization.

This method does not take the environment’s collision model into account.


class ABBIRB1200590(RobotArm)
class ABBIRB1300714(RobotArm)
class ABBIRB1600612(RobotArm)
class ABBIRB460060205(RobotArm)
class ABBIRB6700150320(RobotArm)
class ABBYuMiIRB14000(Robot)
left: ABBYuMiArm
right: ABBYuMiArm
class DualArm(Robot)
left: RobotArm
right: RobotArm
__init__(left: RobotArm, right: RobotArm)
class FanucLR10iA10(RobotArm)
class FanucLRMate200iD7L(RobotArm)
class FanucM20iB25(RobotArm)
class FanucM710iC45M(RobotArm)
class FrankaPanda(RobotArm)
class KinovaGen37DoF(RobotArm)
class KukaIiwa7(RobotArm)
class MecademicMeca500(RobotArm)
class UfactoryXArm7(RobotArm)
class UniversalUR5e(RobotArm)
class UniversalUR10(RobotArm)
class UniversalUR10e(RobotArm)
class UniversalUR20(RobotArm)
class YaskawaGP12(RobotArm)
class YaskawaHC10(RobotArm)
class YaskawaHC20(RobotArm)
class CustomRobot(Robot)

Warning

Custom robots are in a beta preview with rudimentary support right now. If possible, prefer to use robots from our supported robot library, as they will be significantly faster to compute and easier to use.

The translations between the links.

joint_axes: List[List[float]]

The axis of the joints.

joint_types: List[JointType]

The type of the joints: Currently revolute, continuous, prismatic, and fixed joints are supported.

static load_from_urdf_file(file: Path, base_link='base_link', end_link='flange') CustomRobot

Loads a custom robot from a *.urdf file, and sets the robot arm to the kinematic chain between the given base_link and the end_link.

Motions

class LinearSection

Represents a linear Cartesian section for either the approach to the goal or the retraction from the start.

offset: Frame

Relative linear cartesian offset from either the start of the goal.

speed: float = 1.0

Speed of the sub-motion, relative to the overall motion’s speed.

approximation: LinearSection.Approximation = LinearSection.Approximation.Always

To approximate the Cartesian linear motion in joint space for singularity-free calculation.

smooth_transition: bool = True

Whether to use a smooth transition between this and the next or previous section. If false, the robot will come to a complete stop at the transition point.

class Motion

Represents a request for a collision-free point-to-point motion.

name: str

The unique name of the motion.

start: Point

Start point of the motion.

goal: Point

Goal point of the motion.

waypoints: List[Point]

Intermediate waypoints that the motion passes through exactly. The list of waypoints is limited to less than four, otherwise please take a look at LowLevelMotion.

robot: Robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

linear_retraction: LinearSection | None

Optional relative linear cartesian motion for retracting from the start pose.

linear_approach: LinearSection | None

Optional relative linear cartesian motion for approaching the goal pose.

soft_collision_start: bool = False

Enables soft collision checking at the start of the motion. Then, the item obstacle of the robot is allowed to be in collision at the start point. The trajectory will move the item out of collision, and won’t allow a collision thereafter.

soft_collision_goal: bool = False

Enables soft collision checking at the goal of the motion. Then, the item obstacle of the robot is allowed to be in collision at the goal point, but minimizes the time in collision and allows going into collision only once.

path_length_loss_weight: float = 0.1

Weight of the loss minimizing the path length of the trajectory.

orientation_loss_weight: float = 0.0

Weight of the loss minimizing the maximizing deviation of the end-effector orientation to the target value.

orientation_target: List[float] = [0.0, 0.0, 1.0]

Target vector pointing in the direction of the end-effector (TCP) orientation in the world coordinate system.

cartesian_tcp_speed_cutoff: float | None

Optional Cartesian TCP speed (translation-only) cutoff. This is a post-processing step.

initial_waypoints: List[ExactPoint] | None

Optional initial waypoints to start the optimization with (don’t use with intermediate waypoints)

__init__(name: str, robot: Robot, start, goal)
class LinearMotion

Represents a request for a linear Cartesian-space motion.

name: str

The unique name of the motion.

start: Point

Start point of the motion.

goal: Point

Goal point of the motion.

robot: Robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

__init__(name: str, robot: Robot, start: ExactPoint, goal: ExactPoint)
class LowLevelMotion

Represents a request for a low-level motion. While low level motions are not checked for collisions, they are much faster to compute and allow for more flexible constraints such as a minimum duration parameter.

class ControlInterface
Position

Position-control: Full control over the entire kinematic state. (Default)

Velocity

Velocity-control: Ignores the current position, target position, and velocity limits.

class Synchronization
Phase

Phase synchronize the DoFs when possible, else fallback to “Time” strategy. (Default)

Time

Always synchronize the DoFs to reach the target at the same time.

TimeIfNecessary

Synchronize only when necessary (e.g. for non-zero target velocity or acceleration).

None

Calculate every DoF independently.

class DurationDiscretization
Continuous

Every trajectory synchronization duration is allowed. (Default)

Discrete

The trajectory synchronization duration must be a multiple of the control cycle.

name: str

The unique name of the motion.

robot: Robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

start: Waypoint

Start point of the motion.

goal: Waypoint

Goal point of the motion.

intermediate_positions: List[Config]

List of intermediate positions. For a small number of waypoints (less than 16), the trajectory goes exactly through the intermediate waypoints. For a larger number of waypoints, first a filtering algorithm is used to keep the resulting trajectory close to the original waypoints.

minimum_duration: float | None

A minimum duration of the motion.

control_interface: ControlInterface = ControlInterface.Position

The control interface for the motion.

synchronization: Synchronization = Synchronization.Phase

The synchronization strategy for the motion.

duration_discretization: DurationDiscretization = DurationDiscretization.Continuous

The duration discretization strategy for the motion.

__init__(name: str, robot: Robot)

Motion Planning

class Trajectory
id: str

Field for identifying trajectories (for the user).

motion: str

Name of the motion this trajectory was planned for.

duration: float

The trajectory duration in [s].

times: List[float]

The exact time stamps for the position, velocity, and acceleration values. The times will usually be sampled at the delta_time distance of the Planner class, but might deviate at the final step.

positions: List[Config]

The joint positions along the trajectory.

velocities: List[Config]

The joint velocities along the trajectory.

accelerations: List[Config]

The joint accelerations along the trajectory.

reverse() Trajectory

Reverse the trajectory’s start and goal.

append(other: Trajectory)

Appends another trajectory to the current one.

slice(start: int, steps: int) Trajectory

Get a slice of the trajectory starting from step start for a length of steps.

filter_path(max_distance: Config) List[Config]

Filter a path of sparse waypoints from the trajectory.

The path has a maximum distance per degree of freedom between the linear interpolation of the sparse waypoints and the original trajectory.

static from_json_file(file: Path) Trajectory

Loads a trajectory from a *.json file.

to_json_file(file: Path)

Saves a trajectory to a *.json file.

__len__() int

The number of time steps within the trajectory.

as_table() str

To pretty print the trajectory as a table of positions.

class Planner
delta_time: float

The time step for sampling the trajectories from the planner in [s]. Usually, this should correspond to the control rate of the robot.

last_calculation_duration: float

The duration of the last motion planning calculation in [ms].

__init__(environment: Environment, delta_time: float)

Constructs a planner for the given environment.

__init__(robot: Robot, delta_time: float)

Constructs a planner for the given robot and an empty environment.

__init__(project: str, delta_time: float)

Cloud version: Constructs a planner with the environment defined in the given Jacobi Studio project.

static load_from_studio(str: name) Planner

Loads a planner from the Studio project with the given name. It will download and update the project automatically. Requires the JACOBI_API_KEY environment variable to be set.

static load_from_project_file(file: Path) Planner

Loads a planner from a *.jacobi-project file.

add_motion(motion: Motion | LinearMotion | LowLevelMotion)
load_motion_plan(file: Path)

On-prem version: Loads a motion plan from the *.jacobi-plan file.

plan(start: ExactPoint, goal: ExactPoint) Trajectory | None

Plans a time-optimized, collision-free, and jerk-limited motion from start to goal.

plan(motion_name: str, start: ExactPoint = None, goal: ExactPoint = None) Trajectory | None

Plans a time-optimized, collision-free, and jerk-limited motion given the motion name. In case the motion was specified by a start or goal region, the respective exact start or goal positions needs to be passed.

plan(motion: Motion) Trajectory | None

Plans a collision-free point-to-point motion.

plan(motion: LinearMotion) Trajectory | None

Plans a linear motion.

plan(motion: LowLevelMotion) Trajectory | None

Plans a low-level motion.

Studio Live

class Studio

Helper class to connect and visualize trajectories and events in Jacobi Studio.

class Action

An action that can be performed in Jacobi Studio, e.g. setting a robot to a specific joint position or adding an obstacle to the environment.

class Events(dict(list))

A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).

static set_joint_position(joint_position: Config, robot: Robot = None) Action

Returns an action that sets the joint position of the given robot, or the last active robot instead.

static set_item(obstacle: Obstacle | None, robot: Robot = None) Action

Returns an action that sets the item obstacle of the given robot, or the last active robot instead.

static set_material(material: str, robot: Robot = None) Action

Returns an action that sets the material of the given robot, or the last active robot instead.

static add_robot(robot: Robot) Action

Returns an action that adds the given robot to the environment.

static add_obstacle(obstacle: Obstacle) Action

Returns an action that adds the given obstacle to the environment.

static add_waypoint(point: Point) Action

Returns an action that adds the given waypoint to the environment.

static remove_obstacle(obstacle: Obstacle) Action

Returns an action that removes the given obstacle (by name) from the environment.

static set_camera_image_encoded(image: str, camera: Camera = None) Action

Returns an action that sets an image for a camera encoded as a string.

static set_camera_depth_map(depths: list[list[float]], x: float, y: float, camera: Camera = None) Action

Returns an action that sets the depth map visualization of a camera.

__init__()

Connects to Jacobi Studio automatically. Please make sure to enable the Studio Live feature in the Jacobi Studio settings.

speedup: float = 1.0

A factor to speed up or slow down running trajectories or events.

set_joint_position(joint_position: Config, robot: Robot = None)

Sets the joint position of the given robot, or the last active robot instead.

set_item(obstacle: Obstacle | None, robot: Robot = None)

Sets the item obstacle of the given robot, or the last active robot instead.

set_material(material: str, robot: Robot = None)

Sets the material of the given robot, or the last active robot instead.

add_robot(robot: Robot)

Adds the given robot to the environment.

add_obstacle(obstacle: Obstacle)

Adds the given obstacle to the environment.

add_waypoint(point: Point)

Adds the given waypoint to the environment.

remove_obstacle(obstacle: Obstacle)

Removes the given obstacle (by name) from the environment.

set_camera_image_encoded(image: str, camera: Camera = None)

Sets an image for a camera encoded as a string.

set_camera_depth_map(depths: list[list[float]], x: float, y: float, camera: Camera = None)

Sets the depth map visualization of a camera.

run_action(action: Action)

Run the given action in Jacobi Studio.

run_trajectory(trajectory: Trajectory, events: Events = {}, loop_forever=False, robot: Robot = None)

Runs a trajectory for the given robot (or the last active robot) in Jacobi Studio, alongside the events at the specified timings. Optionally, the visualization can be looped.

run_events(events: Events)

Run the events at the specified timings in Jacobi Studio.

reset()

Resets the environment to the state before a trajectory or events were run. In particular, it removes all obstacles there were added dynamically.

get_joint_position(robot: Robot = None) Config

Return the current joint position of the given or only robot.

Robot Driver

class Result
Success = 1

Finished successfully.

Error = -1

General (unspecified) error.

ErrorStartPositionDeviation = -100

The start position of the trajectory deviates from the current robot’s position.

ErrorTrajectoryDidNotUpdate = -101

Failed to update the trajectory.

ErrorReachGoalTimeout = -102

Waiting to reach goal position has timed out.

ErrorCommandAlreadyInProgress = -103

Another command already in progress.

ErrorTrajectoryAborted = -104

Trajectory aborted by stop command.

ErrorController = -200

General error on the controller.

ErrorControllerEStopActive = -201

E-Stop is active on the controller.

ErrorControllerSafetyViolation = -202

Safety violation occured on the controller.

ErrorControllerAlarmActive = -203

An alarm is active on the controller.

ErrorControllerNotInAutoMode = -204

Controller is not in automatic mode.

ErrorControllerNotInRemoteMode = -205

Controller not in a remote mode for external control.

ErrorControllerInHoldState = -206

Controller is in a hold state.

ErrorControllerEnableMotors = -207

The robot’s motors are not enabled.

ErrorControllerProgramStopped = -208

Controller program stopped unexpectedly.

ErrorControllerSendingStop = -209

Failed to send the stop command to the controller.

ErrorControllerConnection = -210

No connection to controller.

class FutureResult
wait() Result

Blocks the code execution until the robot has finished the motion and then returns its result.

property has_finished: bool

Returns whether the corresponding motions has already finished.

class Driver
reconnect() bool

Connect to the robot, in particular after an external disconnection. Returns reconnection success.

disconnect() bool

Disconnect from the robot. Returns disconnection success.

property is_connected: bool

Is the robot currently connected?

property controller_status: ControllerStatus

Current status of the robot’s controller.

enable() Result

Enable robot’s servos (if available).

disable() Result

Disable robot’s servos (if available).

property is_running: bool

Is the robot is currently running a motion in a synchronously or asynchronously manner?

property speed: float

The speed parameter to change the driver’s execution speed. It is usually between 0.0 and 1.0, or might be higher for the SimulatedDriver for faster than real-time speeds.

set_speed(speed: float, duration: float)

Change the speed parameter smoothly with a linear interpolation over the given time duration [s].

property current_joint_position: Config

Returns the current joint position of the robot.

property current_state: RobotState

Returns the current joint state of the robot. Velocity and acceleration information are only available for some drivers.

run(trajectory: Trajectory) Result

Run a trajectory.

run_async(trajectory: Trajectory) FutureResult

Run a trajectory asynchronously.

move_to(goal: ExactPoint, ignore_collision=False) Result

Move to an exact waypoint.

move_to_async(goal: ExactPoint, ignore_collision=False) FutureResult

Move to an exact waypoint asynchronously.

move_along(name: str, ignore_collision=False) Result

Move along a pre-defined motion profile.

move_along_async(name: str, ignore_collision=False) FutureResult

Move along a pre-defined motion profile asynchronously.

blend_into(trajectory: Trajectory, duration: float) Result

Blend into the new trajectory from the current state, so that the robot will be on the given trajectory exactly after the duration time [s].

blend_into_async(trajectory: Trajectory, duration: float) FutureResult

Blend into the new trajectory from the current state, so that the robot will be on the given trajectory exactly after the duration time [s].

stop(fast_stop: bool = True) Result

Stop a motion as fast as possible.

stop_async(fast_stop: bool = True) FutureResult

Stop a motion as fast as possible asynchronously.

create_io_alias(name: str, address: int)

Creates an alias name for a given I/O address.

get_digital_input(name: str) int

Read a digital input.

set_digital_output(name: str, value: int)

Write to a digital output. Returns whether successful.

get_analog_input(name: str) float

Read a analog input.

set_analog_output(name: str, value: float)

Write to a analog output. Returns whether successful.

get_group_input(name: str) int

Read a group input.

set_group_output(name: str, value: int)

Write to a group output. Returns whether successful.

class ABBDriver(Driver)
class RapidModule
__init__(unit='ROB_1', egm_config='default', max_speed_deviation=100.0)

Create a new Rapid module.

__init__(manual_code: str)

Create a module with completly custom manual Rapid code.

unit: str

The name of the robot unit to be controlled.

upload: bool = True

Whether the rapid file should be uploaded to the controller on connection.

add_procedure(name: str, rapid: str)

Adds a procedure to call with arbitrary Rapid code.

get_rapid_code(init='egm') str

Returns the overall Rapid code.

class RWS

A robot connection using the ABB Robot Web Services interface.

class Signal
name: str

The name of the signal.

category: str

The category of the signal.

lvalue: str

The current value of the signal.

property version: str

Get the version of the robot controller.

property robot_type: str

Get the robot type.

property speed_ratio: int

Get and set the robot’s speed ratio.

get_joint_position(mechunit='ROB_1') Config

Get the current robot unit joint position via the RWS interface.

call_procedure(name: str)

Call a Rapid procedure.

execute_rapid_main() Result

Execute the current Rapid program from main.

execute(module: RapidModule, init='egm') Result

Executes the given Rapid module, starting from the given method.

stop_execution()

Stop the execution of the currently running program.

restart_controller()

Restart the controller.

get_signal(signal: str, network='', device='') Signal

Read the signal of the given name.

set_signal(signal: str, value: str, network='', device='')

Write the signal to the given value.

rws: RWS

The RWS module, if initialized.

__init__(planner: Planner, port: int)

Starts an ABB Robot Driver using an underlying EGM server at the specified port.

__init__(planner: Planner, robot: Robot, port: int)

Starts an ABB Robot Driver for a specified robot using an underlying EGM server at the specified port.

__init__(planner: Planner, host: str, module=RapidModule(), version=RobotWareVersion.RobotWare7)

Starts an ABB Robot Driver with an underyling RWS connection.

__init__(planner: Planner, robot: Robot, host: str, module=RapidModule(), version=RobotWareVersion.RobotWare7)

Starts an ABB Robot Driver for a specified robot with an underyling RWS connection.

__init__(planner: Planner, host: str, port: int, module=RapidModule(), version=RobotWareVersion.RobotWare7)

Starts an ABB Robot Driver with both an EGM server and an RWS connection.

__init__(planner: Planner, robot: Robot, host: str, port: int, module=RapidModule(), version=RobotWareVersion.RobotWare7)

Starts an ABB Robot Driver for a specified robot with both an EGM server and an RWS connection.

class SimulatedDriver(Driver)
time_speed: float = 1.0

A factor for speeding up the time, e.g. for faster than real-world simulations.

studio: Studio

The underlying connection to Jacobi Studio.

run_result: Result = Result.Success

The result type for motions.

enable_result: Result = Result.Success

The result type for enabling or disabling the controller.

connect_result: bool = True

The result type for reconnecting or disconnection the controller.

__init__(planner: Planner, sync_with_studio=False, log_stream=False, serve_io_viewer=False)

Starts an Simulated Robot Driver, possibly connecting to Jacobi Studio via Studio Live, or streaming the current positions to cout.

__init__(planner: Planner, robot: Robot, sync_with_studio=False, log_stream=False, serve_io_viewer=False)

Starts an Simulated Robot Driver, possibly connecting to Jacobi Studio via Studio Live, or streaming the current positions to cout. Controls the given robot only.

set_current_joint_position(joint_position: Config)

Sets the current robot’s joint position to the given value.

create_io(name: str, default_value: int | float)

Create a simulated I/O with the given name and default value.

load_io_config(config: list[Signal])

Load a config a list of signals to create multiple I/Os at once.

load_io_config_from_file(file: Path)

Load a config from file to create multiple I/Os at once. The file required to be a *.json with names mapping to their default values.

class UniversalDriver(Driver)
__init__(planner: Planner, host: str)

Starts an Universal Robot Driver using RTDE.

__init__(planner: Planner, robot: Robot, host: str)

Starts an Universal Robot Driver using RTDE. Controls the given robot only.

class YaskawaDriver(Driver)
__init__(planner: Planner, host: str = '192.168.1.31', port: int = 50240)

Starts an Yaskawa Robot Driver connecting to the MotoPlus application running on the robot controller.

__init__(planner: Planner, robot: Robot, host: str = '192.168.1.31', port: int = 50240)

Starts an Yaskawa Robot Driver connecting to the MotoPlus application running on the robot controller. Controls the given robot only.