Python API Reference
You can call help to get the definitions directly from your currently installed Zivid Motion release:
>>> import zividmotion
>>> help(zividmotion.Planner)
Or if you want to look up the entire API at once:
>>> from zividmotion import zividmotion
>>> help(zividmotion)
Units of Measurement
All units in the Zivid Motion API are SI units, meaning meters for length and position and radians for angles.
Application
- class zividmotion.zividmotion.Application
Manager class for Zivid Motion.
The Application class manages resources used by the Zivid Motion. It is required to have one instance of this class alive while using Zivid Motion. Using any part of Zivid Motion without a live Application is undefined behavior.
It is not possible to have more than one Application instance at a time. Creating a second Application instance before the first Application instance has been destroyed will trigger an exception.
- __enter__(self: zividmotion.zividmotion.Application) zividmotion.zividmotion.Application
Enter the runtime context related to this object
- __exit__(self: zividmotion.zividmotion.Application, arg0: type | None, arg1: object | None, arg2: object | None) None
Exit the runtime context related to this object
- create_planner(self: zividmotion.zividmotion.Application, planner_settings: Zivid::Motion::PlannerSettings, use_visualizer: bool = False) Zivid::Motion::Planner
Initializes a Planner instance from planner settings.
- Args:
planner_settings (PlannerSettings): Planner settings
use_visualizer (bool): Whether to open the visualizer.
- Returns:
Planner
- release(self: zividmotion.zividmotion.Application) None
Releases the resources used by the application.
After calling this method, the Application instance should not be used anymore. If you want to use Zivid Motion again, please instantiate a new Application object.
- Returns:
None
- to_string(self: zividmotion.zividmotion.Application) str
Planner
- class zividmotion.zividmotion.Planner
- 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
- clip_point_cloud_with_box(self: zividmotion.zividmotion.Planner, transformed_box: Zivid::Motion::TransformedBox) None
Updates the environment point cloud by removing all points inside the specified box. This is useful when picking up objects from the scene in e.g. de-palletizing applications, where the object being picked up should no longer be considered part of the environment.
- Args:
transformed_box (TransformedBox): The box volume where points should be removed. The transform is defined relative to the cell base frame.
- Returns:
None
- clip_point_cloud_with_mesh(self: zividmotion.zividmotion.Planner, transform: numpy.ndarray[numpy.float32[4, 4]], mesh: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]) None
Updates the environment point cloud by removing all points inside the specified mesh. This is useful when picking up objects from the scene in e.g. de-palletizing applications, where the object being picked up should no longer be considered part of the environment.
- Args:
transform (numpy.ndarray[numpy.float32[4, 4]]): The transformation from the cell base frame to the mesh triangles.
mesh (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): The triangles that make up the mesh. Note: The triangles must form a closed mesh.
- 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.
- Args:
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:
Optional[list[float]]: A configuration that represents the desired pose with the same posture as the reference configuration, or None if no such solution is found.
- export_api_log(self: zividmotion.zividmotion.Planner, output_directory: os.PathLike | None = None) os.PathLike
Exports and saves the API log to file.
- Args:
output_directory (Optional[os.PathLike]): If specified, overrides the default output directory specified in RuntimeConfiguration.yaml.
- Returns:
os.PathLike: The path to the stored API log file.
- get_tcp(self: zividmotion.zividmotion.Planner) zividmotion.zividmotion.Tcp
Returns the current Tool Center Point of the robot.
- Returns:
Tcp: The current TCP.
- path(self: zividmotion.zividmotion.Planner, initial_state: zividmotion.zividmotion.InitialState, request: Zivid::Motion::PathRequest) zividmotion.zividmotion.PathResult
Calculates a path to one of multiple goal configurations from the initial state
- Args:
initial_state (InitialState): The initial state for the path
request (PathRequest): Request for the path call
- Returns:
PathResult
- 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.
- Args:
attachments (list[str]): Specifies the name of the attachments to be set. Only attachments defined in the configuration file can be set. If an empty list is provided, all attachments are removed.
- Returns:
None
- set_carried_object(self: zividmotion.zividmotion.Planner, carried_object: Zivid::Motion::CarriedObject) None
Updates the robot’s collision model with the carried object it’s now holding.
- Args:
carried_object (CarriedObject): The carried object to be set.
- 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.
For colored obstacles, the alpha value is ignored. Note that adding color also has some overhead and is therefore not recommended in performance-critical code.
- Args:
obstacles (list[Obstacle]): Obstacles
- Returns:
None
- set_replaceable_tool(self: zividmotion.zividmotion.Planner, replaceable_tool: Zivid::Motion::ReplaceableTool) None
Updates the robot’s collision model with the current configuration of a modifiable or exchangeable end-effector tool.
- Args:
replaceable_tool (ReplaceableTool): The replaceable tool to be set.
- 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.
- Args:
tcp (Tcp): The TCP to be set.
- Returns:
None
- to_string(self: zividmotion.zividmotion.Planner) str
Helper Classes and Structs
- 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.
- __init__(*args, **kwargs)
Overloaded function.
__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 path result is not available. For consecutive motions, it is recommended to use the PathResult constructor.
- Args:
start_configuration (list[float]): The robot’s start configuration for the path planning
- Returns:
None
__init__(self: zividmotion.zividmotion.InitialState, previous_result: zividmotion.zividmotion.PathResult) -> None
Initializes the InitialState from a PathResult.
This overload is intended for consecutive robot motions. It requires that the provided PathResult has status Success.
- Args:
previous_result (PathResult): A previous successful PathResult
- Returns:
None
- 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 path result is not available. For consecutive motions, it is recommended to use the PathResult constructor.
- Args:
start_configuration (list[float]): The robot’s start configuration for the path planning in touch
- Returns:
InitialState
- to_string(self: zividmotion.zividmotion.InitialState) str
- class zividmotion.zividmotion.PathRequest
Request to pass to a path call.
- __init__(self: zividmotion.zividmotion.PathRequest, type: zividmotion.zividmotion.PathRequest.Type = <Type.free: 0>, goal_prioritization_method: zividmotion.zividmotion.PathRequest.GoalPrioritizationMethod = <GoalPrioritizationMethod.shortestPath: 1>, retract_direction: Optional[Zivid::Motion::Vector3f] = None, goal_configurations: list[list[float]], description: Optional[str] = None) None
Initializes a PathRequest instance.
- Args:
type (Type): The motion type. Defaults to Type.free.
goal_prioritization_method (GoalPrioritizationMethod): Decides which goal is used when multiple reachable goals are provided to the path call. Defaults to GoalPrioritizationMethod.shortestPath.
retract_direction (VectorXYZ, optional): Optional retract direction when retracting from a Touch configuration. When retracting from Touch, this field can be used to specify the desired retraction direction when clearing the surrounding objects. If not provided, the retract direction will be calculated based on the parameters specified in RegionOfInterest. The direction should be given in the cell base frame.
goal_configurations (list[list[float]]): List of goal configurations to plan to. The path will be planned according to the selected goal prioritization method.
description (str, optional): Description can be used to easily distinguish between path calls in the visualizer.
- Returns:
None
- property description
Description can be used to easily distinguish between path calls in the visualizer.
- Returns:
Optional[str]
- property goal_configurations
List of goal configurations to plan to.
The path will be planned according to the selected goal prioritization method.
- Returns:
list[list[float]]
- property goal_prioritization_method
Decides which goal is used when multiple reachable goals are provided to the path call.
- Returns:
GoalPrioritizationMethod
- property retract_direction
Optional retract direction when retracting from a Touch configuration.
When retracting from Touch, this field can be used to specify the desired retraction direction when clearing the surrounding objects. If not provided, the retract direction will be calculated based on the parameters specified in RegionOfInterest. The direction should be given in the cell base frame.
- Returns:
Optional[VectorXYZ]
- to_string(self: zividmotion.zividmotion.PathRequest) str
- property type
Decides the motion type.
- Returns:
Type
- class PathRequest.Type
- free
For moving in free space.
- touch
For interacting with the environment, like 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 InitialState for the path call is constructed from a touch result, then the next trajectory will also start with a linear retraction.
- class PathRequest.GoalPrioritizationMethod
- listOrder
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.
- 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 linear segments, it is then expressed in 3D space, while for joint 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 with what movement type the robot should move to this waypoint.
Note that this can affect how the blend_radius should be interpreted for both this and the previous waypoint in the path.
- Returns:
Movement
- to_string(self: zividmotion.zividmotion.Waypoint) str
- class Waypoint.Movement
- joint
The robot moves linearly in joint space (often called move_j).
- linear
The robot moves linearly in cartesian space (often called move_l).
- class zividmotion.zividmotion.PathResult
PathResult 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.PathResult) bool
Returns true if there is no planning error, false otherwise.
Makes it convenient to do
if path_result: ...- Returns:
bool: A boolean indicating successful status.
- property error
The PathResult will have an error set if the planner did not find a collision-free path to any of the goals.
- Returns:
Optional[Error]: The error of the path result, if any.
- property final_configuration
Returns the final configuration of the robot in the computed path.
This is the same as the selected goal and performs the same operation as calling
.path[-1].configuration. This throws if the path planning failed.- Returns:
list[float]: The final configuration of the path.
- 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. The final waypoint in the path is the joint configuration of the selected goal, i.e.:
plan_result.final_configuration == goals[plan_result.selected_goal_idx].configuration.If there is a planning error, the list is empty.
- Returns:
list[Waypoint]: A list of waypoints.
- property selected_goal_idx
If there is a planning error, this is None. Otherwise, this is the index to the selected goal in the goals vector.
- Returns:
Optional[int]: The selected goal’s index in the list of goals, if any.
- property tcp
The TCP when the PathResult was computed.
- Returns:
Tcp
- to_string(self: zividmotion.zividmotion.PathResult) str
- class PathResult.Error
- blockedStart
The start configuration is blocked.
- blockedEnd
All the valid goal configurations are blocked.
- blockedPath
The start configuration and at least one goal configuration are not blocked, but the planner failed to connect them with a collision-free path.
- kinematicViolation
All the goal configurations are outside the robot’s joint limits.
- class zividmotion.zividmotion.Obstacle
Represents an obstacle in the robot environment, to be used with the set_obstacles() method. The obstacle coordinates must be expressed in the base frame of the planner.
- static from_colored_mesh(name: str, mesh: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]], color: Annotated[list[int], FixedSize(4)]) zividmotion.zividmotion.Obstacle
Initializes a colored Obstacle instance from a triangle mesh geometry.
Note that adding color has some overhead and is therefore not recommended in performance-critical code.
- Args:
name (str): Name
mesh (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): The mesh defining the obstacle surface.
color (Annotated[list[int], FixedSize(4)]): The color of the obstacle
- Returns:
Obstacle
- static from_colored_point_cloud(name: str, points: list[Annotated[list[float], FixedSize(3)]], colors: list[Annotated[list[int], FixedSize(4)]]) zividmotion.zividmotion.Obstacle
Initializes a colored Obstacle instance from a point cloud.
The number of points and colors must be the same. Note that adding color has some overhead and is therefore not recommended in performance-critical code.
- Args:
name (str): Name
points (list[Annotated[list[float], FixedSize(3)]]): Points
colors (list[Annotated[list[int], FixedSize(4)]]): Colors
- Returns:
Obstacle
- static from_mesh(name: str, mesh: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]) zividmotion.zividmotion.Obstacle
Initializes an Obstacle instance from a triangle mesh geometry.
- Args:
name (str): Name
mesh (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): The mesh defining the obstacle surface.
- Returns:
Obstacle
- static from_point_cloud(name: str, points: list[Annotated[list[float], FixedSize(3)]]) zividmotion.zividmotion.Obstacle
Initializes an Obstacle instance from a point cloud.
- Args:
name (str): Name
points (list[Annotated[list[float], FixedSize(3)]]): Points
- Returns:
Obstacle
- to_string(self: zividmotion.zividmotion.Obstacle) str
- class zividmotion.zividmotion.CarriedObject
Represents an object that the robot carries during motion planning, to be used with the set_carried_object() method. When the carried object is set on the robot, this geometry is added to the robot’s collision model. The carried object is defined in the robot TCP frame.
- static from_box(transformed_box: zividmotion.zividmotion.TransformedBox) zividmotion.zividmotion.CarriedObject
Creates a CarriedObject from a box-shaped geometry.
- Args:
transformed_box (TransformedBox): The box geometry with its transform and dimensions.
- Returns:
CarriedObject: The created CarriedObject instance.
- static from_mesh(transform: numpy.ndarray[numpy.float32[4, 4]], mesh: list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]) zividmotion.zividmotion.CarriedObject
Initializes a CarriedObject instance from a triangle mesh geometry.
- Args:
transform (numpy.ndarray[numpy.float32[4, 4]]): The transform of the mesh vertices.
mesh (list[Annotated[list[Annotated[list[float], FixedSize(3)]], FixedSize(3)]]): The list of triangles defining the object surface.
- Returns:
CarriedObject: The created CarriedObject instance.
- to_string(self: zividmotion.zividmotion.CarriedObject) str
- class zividmotion.zividmotion.ReplaceableTool
Represents a replaceable tool that can be mounted on the robot, to be used with the set_replaceable_tool() method. When the replaceable tool is set on the robot, this geometry is added to the robot’s collision model. The replaceable tool is defined in the robot flange frame.
- static from_box_elements(tool_elements: list[zividmotion.zividmotion.ToolBoxElement]) zividmotion.zividmotion.ReplaceableTool
Creates a ReplaceableTool from a list of ToolElements.
- Args:
tool_elements (list[ToolBoxElement]): A list of tool box elements.
- Returns:
ReplaceableTool: The created ReplaceableTool instance.
- to_string(self: zividmotion.zividmotion.ReplaceableTool) str
- class zividmotion.zividmotion.ToolBoxElement
A tool element consisting a rigid and an optional compliant box geometry.
- __init__(self: zividmotion.zividmotion.ToolBoxElement, transform: numpy.ndarray[numpy.float32[4, 4]], box_dimensions: Annotated[list[float], FixedSize(3)], compliant_box: zividmotion.zividmotion.TransformedBox | None = None) None
Initializes a ToolBoxElement instance from a transform, rigid box dimensions and an optional compliant box.
- Args:
transform (numpy.ndarray[numpy.float32[4, 4]]): The transformation of the tool element relative to the flange frame.
box_dimensions (Annotated[list[float], FixedSize(3)]): The bottom centered box dimensions representing the rigid geometry of the tool element.
compliant_box (Optional[TransformedBox]): Optional bottom centered transformed box representing the compliant geometry of the tool element during Touch motions. This could represent the deformable part of a suction gripper. Environment contact will be allowed for the specified geometry during Touch motions, while it will be considered rigid all other times. The compliant box is defined relative to the tool element transform.
- Returns:
None
- to_string(self: zividmotion.zividmotion.ToolBoxElement) str
- class zividmotion.zividmotion.Tcp
Represents a tool center point (TCP) of the robot. It contains the transform and tool direction.
- __init__(self: zividmotion.zividmotion.Tcp, transform: numpy.ndarray[numpy.float32[4, 4]], tool_direction: numpy.ndarray[numpy.float32[3, 1]]) None
Initializes a TCP instance from a transform and tool direction.
- Args:
transform (numpy.ndarray[numpy.float32[4, 4]]): Transform
tool_direction (numpy.ndarray[numpy.float32[3]]): Tool direction
- Returns:
None
- to_string(self: zividmotion.zividmotion.Tcp) str
- property tool_direction
The tool direction of the TCP, expressed in the new TCP frame.
This is used for interaction planning in Touch operations.
- Returns:
numpy.ndarray[numpy.float32[3]]
- property transform
The transform of the TCP, relative to the robot flange frame.
- Returns:
numpy.ndarray[numpy.float32[4, 4]]
- class zividmotion.zividmotion.PlannerSettings
Settings to instantiate the Planner.
- __init__(self: zividmotion.zividmotion.PlannerSettings, cell_name: str, profile: zividmotion.zividmotion.Profile) None
Initializes a PlannerSettings instance.
- Args:
cell_name (str): The identifier for the planner configuration data path
profile (Profile): Used to specify a testing or production profile for a robot cell
- Returns:
None
- to_string(self: zividmotion.zividmotion.PlannerSettings) str
- class zividmotion.zividmotion.TransformedBox
Represents a box with a given transform.
- __init__(self: zividmotion.zividmotion.TransformedBox, bottom_centered_transform: numpy.ndarray[numpy.float32[4, 4]], box_dimensions: Annotated[list[float], FixedSize(3)]) None
Initializes a TransformedBox instance from a transform and box dimensions.
- Args:
bottom_centered_transform (numpy.ndarray[numpy.float32[4, 4]]): The transformation from the context-dependent reference frame to the box bottom center.
box_dimensions (Annotated[list[float], FixedSize(3)]): The dimensions of the box.
- Returns:
None
- to_string(self: zividmotion.zividmotion.TransformedBox) str
- class zividmotion.zividmotion.VectorXYZ
- to_string(self: zividmotion.zividmotion.VectorXYZ) str
Free Functions
- zividmotion.zividmotion.generate(application: (anonymous namespace)::ReleasableApplication, planner_settings: Zivid::Motion::PlannerSettings, progress_callback: Callable[[float, str], None] = None) None
Generate cell data
- Args:
application (Application): Motion application
planner_settings (PlannerSettings): Settings for generation
progress_callback (Callable[[float, str], None] or None): An optional progress callback function
- Returns:
None
- zividmotion.zividmotion.package_cell(application: (anonymous namespace)::ReleasableApplication, cell_name: str, output_path: os.PathLike, include_generated_data: list[zividmotion.zividmotion.Profile]) None
Packages a cell into a zip archive.
This function collects all files required to execute the planner with the specified cell name and packages them into a zip file at the given output path.
Throws if the specified cell does not exist, if the output file already exists, or if the parent folder of the output path does not exist.
- Args:
application (Application): Motion application
cell_name (str): The name of the cell to package.
output_path (os.PathLike): The destination path for the generated zip archive, including the filename with “.zip” extension.
include_generated_data (list[Profile]): What generated data to include.
- Returns:
None
- zividmotion.zividmotion.package_api_log(application: (anonymous namespace)::ReleasableApplication, 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.zipsuffix instead of the.jsonextension. The API log itself is not packaged.- Args:
application (Application): Motion application
api_log_path (os.PathLike): The path to the API log
- Returns:
os.PathLike: The path to the created zip archive.
- zividmotion.zividmotion.install_package(application: (anonymous namespace)::ReleasableApplication, package_path: os.PathLike) None
Installs a packaged cell to be used by the Planner.
This function extracts the contents of a packaged cell (zip archive) and installs them into the appropriate directory so they can be used by the Planner.
- Args:
application (Application): Motion application
package_path (os.PathLike): The path to the cell package (zip archive) to install.
- Returns:
None