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.

property base: FrameΒΆ

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.

static from_model(model: str) RobotΒΆ

Returns the robot with the given model name.

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 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.