Python API Reference

Introduction

This is the reference for Zivid Motion Python API.

You can call help to get the definitions directly from your currently installed Zivid Motion release:

>>> from zividmotion import zividmotion
>>> help(zividmotion)

Or be specific if you want to look up a specific part of the API:

>>> from zividmotion import zividmotion
>>> help(zividmotion.Planner)

Our goal is to provide complete and separate API reference, documentation and examples for each release. But for now, if you see anything that does not match with your currently installed release, have questions or feedback, please contact the Zivid Motion team directly at oystein.holhjem@zivid.com.

API Reference

Note

Always use keyword arguments when calling methods with overloads, e.g planner.path(initial_state=initial_state, goal_configurations=goal_configurations). The Python API is generated from C++ code using pybind11, and you may invoke another overload than you expect if you’re not being explicit.

class zividmotion.zividmotion.GenerationSettings

Settings to pass to generate.

generation_settings = GenerationSettings.from_dict({
  "DataTag": str,
  "GenerateConfig": Literal["Testing", "Production"],
})

DataTag is the identifier for the planner configuration data path.

GenerateConfig Selects which config to generate for.

static from_dict(dictionary: dict) zividmotion.zividmotion.GenerationSettings
property data_tag
property generate_config
class zividmotion.zividmotion.InitialState

Represents the context required for path planning. It is used as an argument to the Planner::path method.

The InitialState class encapsulates the start configuration or the result of a path planning operation. It is used to provide the necessary context for planning paths to goal configurations.

static from_touch(start_configuration: list[float]) zividmotion.zividmotion.InitialState

Initializes the InitialState from a start Configuration in touch. In contrast to the regular constructor, this function is used when the robot is in a touch state. This should only be utilized when a previous plan result is not available. For consecutive motions, it is recommended to use the PlanResult constructor.

Parameters:

start_configuration (list[float]) – The robot’s start configuration for the path planning in touch

Returns:

InitialState

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: zividmotion.zividmotion.InitialState, start_configuration: list[float]) -> None

    Initializes the InitialState from a start Configuration

    This should only be utilized when a previous plan result is not available. For consecutive motions, it is recommended to use the PlanResult constructor.

    Args:

    start_configuration (list[float]): The robot’s start configuration for the path planning

    Returns:

    None

  2. __init__(self: zividmotion.zividmotion.InitialState, previous_result: zividmotion.zividmotion.PlanResult) -> None

    Initializes the InitialState from a PlanResult

    This overload is intended for consecutive robot motions. It requires that the provided PlanResult has status Success.

    Args:

    previous_result (PlanResult): A previous successful PlanResult

    Returns:

    None

class zividmotion.zividmotion.Movement

Members:

joint

linear

joint = <Movement.joint: 0>
linear = <Movement.linear: 1>
class zividmotion.zividmotion.Obstacle

Represents an obstacle in the robot environment, to be used with the set_obstacles() method. It can be constructed from different data types.

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, points: list[Annotated[list[float], FixedSize(3)]]) -> None

    Initializes an Obstacle instance from a point cloud.

    Args:

    name (str): Name points (list[Annotated[list[float], FixedSize(3)]]): Points

    Returns:

    None

  2. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, points: list[Annotated[list[float], FixedSize(3)]], colors: list[Annotated[list[int], FixedSize(3)]]) -> None

    Initializes a colored Obstacle instance from a point cloud.

    Important: Colored obstacles impact performance. Avoid using them in production.

    Args:

    name (str): Name points (list[Annotated[list[float], FixedSize(3)]]): Points colors (list[Annotated[list[int], FixedSize(3)]]): Colors

    Returns:

    None

  3. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, triangles: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]) -> None

    Initializes an Obstacle instance from a list of triangles.

    Args:

    name (str): Name triangles (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): Triangles

    Returns:

    None

  4. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, triangles: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]], color: Annotated[list[int], FixedSize(3)]) -> None

    Initializes a colored Obstacle instance from a list of triangles.

    Important: Colored obstacles impact performance. Avoid using them in production.

    Args:

    name (str): Name triangles (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): Triangles color (color: Annotated[list[int], FixedSize(3)]): Color

    Returns:

    None

  5. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, structured_points: numpy.ndarray[numpy.float32]) -> None

    Initializes an Obstacle instance from a structured point cloud.

    Args:

    name (str): Name structured_points: numpy.ndarray[numpy.float32]

    Returns:

    None

  6. __init__(self: zividmotion.zividmotion.Obstacle, *, name: str, structured_points: numpy.ndarray[numpy.float32], colors: numpy.ndarray[numpy.uint8]) -> None

    Initializes a colored Obstacle instance from a structured point cloud.

    Important: Colored obstacles impact performance. Avoid using them in production.

    Args:

    name (str): Name structured_points: numpy.ndarray[numpy.float32] colors: numpy.ndarray[numpy.uint8]

    Returns:

    None

property name

The name of the obstacle.

Returns:

str

class zividmotion.zividmotion.PathSettings

PathSettings is used to configure parameters in a Planner.path call.

path_settings = PathSettings.from_dict({
  "Type": Literal["Touch", "Free"],
  "GoalPrioritizationMethod":  Literal["ShortestPath", "ListOrder"],
})

Type decides the motion type.

  • Free: (Default) For moving in free space.

  • Touch: For gripping or placing an object. A touch call will include a linear motion at the end of the trajectory to approach the object safely. If the path overload for consecutive motions is used and the previous plan result came from a touch call, then the next trajectory will also start with a linear retraction.

GoalPrioritizationMethod decides which goal is used when multiple reachable goals are provided to the Planner.path call. Valid options are:

  • ListOrder: (Default) Among the reachable goals, the one that appears first in the list of goals is selected.

  • ShortestPath: Among the reachable goals, the one that gives the shortest trajectory is selected.

static from_dict(dictionary: dict) zividmotion.zividmotion.PathSettings
property type
property goal_prioritization_method
class zividmotion.zividmotion.PlanResult

PlanResult is the result of calculating a path to a set of potential goals. It’s the return value from Planner.path().

__bool__(self: zividmotion.zividmotion.PlanResult) bool

Returns True if status == Status.success, False otherwise. Makes it convenient to do if planResult …

Returns:

A boolean indicating successful status.

Return type:

bool

property path

Returns the computed path, as a list of waypoints. The path does not include the start configuration provided to the Planner.path() call. And the final waypoint in the path is the joint configuration of the selected goal, meaning: path[-1].configuration == goals[executed_goal_id].configuration). If status != Status.success the list is empty.

Returns:

A list of waypoints.

Return type:

list[Waypoint]

property selected_goal_idx

If status == Status.success, this is the index to the selected goal in the list of goals. If status != Status.success, this is None.

Returns:

The selected goal’s index in the list of goals.

Return type:

int

property status

The PlanResult will have status set to success if the planner found a collision-free path to one of the goals. If a collision-free path was not found, the status describes why so.

Returns:

The staus of the plan result.

Return type:

Status

property tcp

The TCP when the PlanResult was computed.

Returns:

Tcp

class zividmotion.zividmotion.Planner
__init__(self: zividmotion.zividmotion.Planner, *, planner_settings: zividmotion.zividmotion.PlannerSettings) None

Initializes a Planner instance from planner settings.

Parameters:

planner_settings (PlannerSettings) – Planner settings

Returns:

None

check_mesh_collisions(self: zividmotion.zividmotion.Planner, *, configurations: list[list[float]], num_ignored_links_from_tip: int) list[bool]

Checks if the robot is in collision with any environment meshes for the given joint configurations. Also checks for self-collision. Any environment point clouds are ignored.

Use num_ignored_links_from_tip to disregard links of the robot from collision checking, counting from the tip of your robot model. Use the value zero to include the whole robot model. Note that if you have a tool modeled as part of the last link, then setting this to 1 ignores the tool as well. Any carried objects or replaceable tools are also ignored when num_ignored_links_from_tip > 0.

Also note that including multiple configurations in the same call is faster than iterative calls to this method.

Parameters:
  • configurations (list[list[float]]) – Configurations

  • num_ignored_links_from_tip (int) – Number of ignored links from tip

Returns:

One bool per input configuration. True if the configuration is in collision, False otherwise.

Return type:

list[bool]

clear_carried_object(self: zividmotion.zividmotion.Planner) None

Clears the carried object from the robot’s collision model.

Returns:

None

clear_obstacles(self: zividmotion.zividmotion.Planner) None

Clears all registered obstacles from the planner’s collision model.

Returns:

None

clear_replaceable_tool(self: zividmotion.zividmotion.Planner) None

Clears the replaceable tool from the robot’s collision model.

Returns:

None

compute_inverse_kinematics(self: zividmotion.zividmotion.Planner, *, pose: numpy.ndarray[numpy.float32[4, 4]], reference_configuration: list[float]) list[float] | None

Computes the robot’s joint configuration corresponding to the given TCP pose

This method performs inverse kinematics to find the joint configuration. There are possibly multiple joint configurations that correspond to the same TCP pose, denoted by different robot postures. The reference configuration is used to select which posture the solution should be computed for.

Parameters:
  • pose (numpy.ndarray[numpy.float32[4, 4]]) – The pose for which the corresponding configuration will be computed

  • reference_configuration (list[float]) – A reference configuration used to preserve the robot’s posture

Returns:

A configuration that represents the desired pose with the same posture as the

reference configuration, or None if no such solution is found.

Return type:

Optional[list[float]]

export_api_log(self: zividmotion.zividmotion.Planner, *, output_directory: os.PathLike | None = None) str

Exports and saves the API log to file.

Parameters:

output_directory (Optional[str]) – If specified, overrides the default output directory specified in RuntimeConfiguration.yaml.

Returns:

The path to the stored API log file.

Return type:

str

get_tcp(self: zividmotion.zividmotion.Planner) zividmotion.zividmotion.Tcp

Returns the current Tool Center Point of the robot.

Returns:

The current TCP.

Return type:

Zivid.Motion.Tcp

path(self: zividmotion.zividmotion.Planner, *, initial_state: zividmotion.zividmotion.InitialState, goal_configurations: list[list[float]], path_settings: zividmotion.zividmotion.PathSettings = PathSettings: GoalPrioritizationMethod: ListOrder RetractDirection: X: __not_set__ Y: __not_set__ Z: __not_set__ Type: Free, description: Optional[str] = None) zividmotion.zividmotion.PlanResult

Calculates a path to one of multiple goal configurations from the initial state

Parameters:
  • initial_state (InitialState) – The initial state for the path (created from a start configuration or a plan result)

  • goal_configurations (list[list[float]]) – Goal configurations

  • path_settings (PathSettings) – Settings for the path call

  • description (string, optional) – Description can be used to easily distinguish between path calls in the visualizer

Returns:

PlanResult

set_attachments(self: zividmotion.zividmotion.Planner, *, attachments: list[str]) None

Sets the active attachments connected to the last link of the robot in the robot’s collision model. Multiple attachments can be added. Only attachments defined in the configuration file can be added.

Parameters:

attachments (list[str]) – Specifies the name of the attachments to be set. Only attachments defined in the configuration file can be set.

Returns:

None

set_carried_object(*args, **kwargs)

Overloaded function.

  1. set_carried_object(self: zividmotion.zividmotion.Planner, *, transform: numpy.ndarray[numpy.float32[4, 4]], box_dimensions: Annotated[list[float], FixedSize(3)]) -> None

    Updates the robot’s collision model with a bounding box of the object it’s now holding.

    Args:
    transform (numpy.ndarray[numpy.float32[4, 4]]): Transform is a transformation from the current TCP

    frame to the bottom center position of the object bounding box. The translation is applied in the TCP frame (not the final rotated frame) and should be specified in millimeters. Note that “bottom” is here meant locally; if the z-axis of the transformed TCP frame points downwards, the “bottom” center will be on top of the object.

    box_dimensions (Annotated[list[float], FixedSize(3)]): Dimensions of the bounding box in the x, y and z direction

    of the transformed TCP frame. This should be specified in millimeters.

    Returns:

    None

  2. set_carried_object(self: zividmotion.zividmotion.Planner, *, transform: numpy.ndarray[numpy.float32[4, 4]], triangles: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]) -> None

    Updates the robot’s collision model with a mesh of the object it’s now holding.

    Args:
    transform (numpy.ndarray[numpy.float32[4, 4]]): Transform is a transformation from the current TCP

    frame to the triangle mesh. The translation part should be specified in millimeters.

    Note: Ensure that the underlying data type (dtype) for the arguments is float32

    triangles (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): Triangles specifying the mesh of the carried

    object. This should be specified in millimeters.

    Returns:

    None

set_obstacles(self: zividmotion.zividmotion.Planner, *, obstacles: list[zividmotion.zividmotion.Obstacle]) None

Register objects in the environment for collision avoidance. Obstacles are unique by name, if you set a new obstacle with the same name as an existing obstacle, the existing one will be replaced. When possible, it is preferred to set all obstacles at once with a single call, rather than iterative calls to this method which will be slower.

The obstacle coordinates must be expressed in the base frame of the planner and given in mm. Point-based obstacles can contain NAN values, the invalid points will simply be ignored. For colored obstacles, the alpha value is ignored. Adding color also has some overhead and is therefore not recommended in performance-critical code.

Parameters:

obstacles (list[Obstacle]) – Obstacles

Returns:

None

set_replaceable_tool(self: zividmotion.zividmotion.Planner, *, transform: numpy.ndarray[numpy.float32[4, 4]], box_dimensions: Annotated[list[float], FixedSize(3)]) None

Updates the robot’s collision model with a bounding box of the current configuration of a modifyable or exchangeable end-effector tool.

Parameters:
  • transform (numpy.ndarray[numpy.float32[4, 4]]) – Transform is a transformation from the robot flange frame defined in your config file to the bottom center position of the tool bounding box. Translation is applied in the reference frame (not the final rotated frame) and should be specified in millimeters. Note that “bottom” is here meant locally; if the z-axis of the transformed reference frame points downwards, the “bottom” center will be on top of the tool.

  • box_dimensions (Annotated[list[float], FixedSize(3)]) – Dimensions of the bounding box in the x, y and z direction of the transformed reference frame. This should be specified in millimeters.

Returns:

None

set_tcp(self: zividmotion.zividmotion.Planner, *, tcp: zividmotion.zividmotion.Tcp) None

Updates the current Tool Center Point of the robot. The new TCP frame is used for path planning to goal poses, and it is the reference frame for setting carried objects.

Parameters:

tcp (Tcp) – The TCP to set.

Returns:

None

class zividmotion.zividmotion.PlannerSettings

Settings to instantiate Planner.

planner_settings = PlannerSettings.from_dict({
  "DataTag": str,
  "CellConfig": str,
  "UseVisualizer": bool,
})
static from_dict(dictionary: dict) zividmotion.zividmotion.PlannerSettings
property cell_config
property data_tag
property use_visualizer
class zividmotion.zividmotion.Status

Members:

success

blockedStart

blockedEnd

blockedPath

kinematicViolation

success = <Status.success: 0>
blockedStart = <Status.blockedStart: 1>
blockedEnd = <Status.blockedEnd: 2>
blockedPath = <Status.blockedPath: 3>
kinematicViolation = <Status.kinematicViolation: 4>
class zividmotion.zividmotion.Tcp

Represents a tool center point (TCP) of the robot. It contains the transform and tool direction.

property tool_direction

The tool direction of the TCP. Assuming the TCP represents some tool that interacts with the environment, the tool_direction should be set to the direction the tool is pointing in, expressed in the new TCP frame. This determines in what direction linear motions are performed when the path planning includes this in the trajectory. The direction does not have to be normalized. If the start/goal is inside a region of interest with a defined escape direction, this will override the tool direction.

Returns:

numpy.ndarray[numpy.float32[3]]

property transform

The transform of the TCP. Transform is the transformation from the robot flange frame defined in your config file to the new TCP frame. Translation is applied in the default TCP frame (not in the final rotated frame) and should be specified in millimeters.

Returns:

numpy.ndarray[numpy.float32[4, 4]]

class zividmotion.zividmotion.Waypoint

A waypoint in joint space, describing where and how the robot should move as part of a path.

property blend_radius

The blend radius for this waypoint guaranteed to give a collision-free blending path, specified for the entry and exit path segment respectively. The first number is the distance from the waypoint to the point along the trajectory from the previous waypoint to the current one where safe blending can start. The second number is the distance from the waypoint to the point along the trajectory from the current waypoint to the next one where safe blending must end.

How to interpret the blend radius depends on the robot in use. If the robot supports single-valued TCP blending, the entry and exit values will always be equal and expressed in 3D space. If the robot doesn’t support single-valued TCP blending, the blend radius is specified individually for the entry and exit segments. For move_l segments, it is then expressed in 3D space, while for move_j segments, it is expressed in joint space.

Blend radiuses given in 3D space are always given in meters and represent the distance the current TCP can be from its position at the waypoint configuration when blending should start and/or end. While blend radiuses given in joint space represents the euclidian distance (L2-norm) between the waypoint configuration and the joint configuration where the blending should start or end. When computing the distance in joint space, rotational joints are represented in radians and if the robot has any linear joints they are represented in meters.

Do not use a smaller non-zero blend radius than what is reported. Either use the value(s) provided or zero. Smaller non-zero values are not guaranteed to give collision-free blending motions in all scenarios.

Note that the blend radius will never be more than half the distance between consecutive waypoints.

Returns:

tuple[float, float]

property configuration

The joint configuration of the waypoint.

Returns:

list[float]

property movement

Describes if the robot should move linearly in joint space or in cartesian space to this waypoint (e.g. move_j or move_l).

Returns:

Movement

zividmotion.zividmotion.create_box_mesh(*, center_point: Annotated[list[float], FixedSize(3)], size: Annotated[list[float], FixedSize(3)]) list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]

Creates a box mesh given a center point and the size of the box. The center point is expressed in the planner base frame.

Parameters:
  • center_point (Annotated[list[float], FixedSize(3)]) – Center point

  • size (Annotated[list[float], FixedSize(3)]) – Size

Returns:

A list of triangles that represent a box mesh.

Return type:

list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]

zividmotion.zividmotion.generate(*, generation_settings: zividmotion.zividmotion.GenerationSettings, progress_callback: Callable[[float, str], None] = None) None

Generate cell data

Parameters:
  • generation_settings (GenerationSettings) – Generation settings

  • progress_callback (Callable[[float, str], None] or None) – An optional progress callback function

Returns:

None

zividmotion.zividmotion.package_data_tag(*, data_tag: str, output_path: os.PathLike, include_generated_data: list[str]) None

Packages a data tag into a zip archive.

This function collects all files required to execute the planner with the specified data tag and packages them into a zip file at the given output path.

Parameters:
  • data_tag (str) – The name of the data tag to package.

  • output_path (str) – The destination path for the generated zip archive.

  • include_generated_data (list[str]) – What generated data to include (Testing/Production).

Returns:

None

zividmotion.zividmotion.package_api_log(*, api_log_path: os.PathLike) os.PathLike

Packages the data related to an API log into a zip archive.

This function collects the files required to replay a motion session with a specified API log, and packages them into a zip file with the same name as the API log, but with the -resources.zip suffix instead of the .json extension. The API log itself is not packaged.

Parameters:

api_log_path (str) – The path to the API log

Returns:

The path to the created zip archive.

Return type:

str

zividmotion.zividmotion.install_package(*, package_path: os.PathLike) None

Installs a packaged data tag to be used by the Planner.

This function extracts the contents of a packaged data tag (zip archive) and installs them into the appropriate directory so they can be used by the Planner.

Parameters:

package_path (str) – The path to the data tag package (zip archive) to install.

Returns:

None