C++ API Reference

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

Public Functions

Planner createPlanner(PlannerSettings plannerSettings, bool useVisualizer = false) const

Initializes a Planner instance from planner settings.

Parameters:
  • plannerSettingsPlanner settings

  • useVisualizer – Whether to open the visualizer


Planner

class Planner

Public Functions

std::optional<Configuration> computeInverseKinematics(const Pose &pose, const Configuration &referenceConfiguration) const

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 – The pose for which the corresponding configuration will be computed

  • referenceConfiguration – 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 std::nullopt if no such solution is found.

PathResult path(const InitialState &initialState, const PathRequest &request) const

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

Parameters:
  • initialState – The initial state for the path

  • request – Request for the path call

void setObstacles(const std::vector<Obstacle> &obstacles) const

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.

Parameters:

obstacles – Obstacles

void clearObstacles() const

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

void setCarriedObject(const CarriedObject &carriedObject) const

Updates the robot’s collision model with the carried object it’s now holding.

Parameters:

carriedObject – The carried object to be set

void clearCarriedObject() const

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

void setReplaceableTool(const ReplaceableTool &replaceableTool) const

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

Parameters:

replaceableTool – The replaceable tool to be set

void clearReplaceableTool() const

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

void setAttachments(const std::vector<std::string> &attachments) const

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 – Specifies the name of the attachments to be set. Only attachments defined in the configuration file can be set. If an empty vector is provided, all attachments are removed.

void setTcp(const Tcp &tcp) const

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 – The TCP to be set

Tcp getTcp() const

Returns the current Tool Center Point of the robot.

Returns:

The current TCP

void clipPointCloudWithBox(const TransformedBox &box)

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.

Parameters:

box – The box volume where points should be removed. The transform is relative to the cell base frame.

void clipPointCloudWithMesh(const Pose &transform, const Triangles &mesh)

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.

Parameters:
  • transform – The transformation from the cell base frame to the mesh triangles.

  • mesh – The triangles that make up the mesh. Note: The triangles must form a closed mesh.

std::filesystem::path exportApiLog(const std::optional<std::filesystem::path> &outputDirectory = std::nullopt) const

Exports and saves the API log to file.

Parameters:

outputDirectory – If specified, overrides the default output directory specified in RuntimeConfiguration.yaml.

Returns:

The path to the stored API log file.

std::string toString() const

Get string-representation of Planner


Helper Classes and Structs

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

Public Functions

InitialState(const Configuration &startConfiguration)

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.

Parameters:

startConfiguration – The robot’s start configuration for the path planning

InitialState(const PathResult &previousResult)

Initializes the InitialState from a PathResult.

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

Parameters:

previousResult – A previous successful PathResult

Public Static Functions

static InitialState FromTouch(const Configuration &startConfiguration)

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.

Parameters:

startConfiguration – The robot’s start configuration for the path planning in touch

struct PathRequest

Request to pass to a path call.

Public Types

enum class Type

Used to specify the motion type.

Values:

enumerator free

For moving in free space.

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

enum class GoalPrioritizationMethod

Used to specify the goal prioritization method.

Values:

enumerator listOrder

Among the reachable goals, the one that appears first in the list of goals is selected.

enumerator shortestPath

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

Public Members

Type type = Type::free

Decides the motion type.

GoalPrioritizationMethod goalPrioritizationMethod = GoalPrioritizationMethod::shortestPath

Decides which goal is used when multiple reachable goals are provided to the path call.

std::optional<VectorXYZ> retractDirection = {}

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.

std::vector<Configuration> goalConfigurations

List of goal configurations to plan to.

The path will be planned according to the selected goal prioritization method.

std::optional<std::string> description

Description can be used to easily distinguish between path calls in the visualizer.

std::optional<float> maxCarriedObjectCompressionDistance = {}

Optional parameter for specifying the maximum compression distance, beyond initial contact, for the carried object along the Touch approach.

struct BlendRadius

Represents a blend radius for a given waypoint.

Public Members

float entry

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

float exit

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

struct Waypoint

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

Public Types

enum class Movement

Enum describing different ways the robot can move between waypoints.

Values:

enumerator joint

The robot moves linearly in joint space (often called moveJ).

enumerator linear

The robot moves linearly in cartesian space (often called moveL).

Public Members

Configuration configuration

The joint configuration of the waypoint.

Movement movement

Describes with what movement type the robot should move to this waypoint.

Note that this can affect how the BlendRadius should be interpreted for both this and the previous waypoint in the path.

BlendRadius blendRadius

The blend radius for this waypoint guaranteed to give a collision-free blending path, specified for the entry and exit path segment respectively.

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.

class PathResult

PathResult is the result of calculating a path to a set of potential goals.

It’s the return value from Planner.path().

Public Types

enum class Error

Enum describing why the planner did not find a path to any goal.

Values:

enumerator blockedStart

The start configuration is blocked.

enumerator blockedEnd

All the valid goal configurations are blocked.

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

enumerator kinematicViolation

All the goal configurations are outside the robot’s joint limits.

Public Functions

Path path() const

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, i.e.: planResult.finalConfiguration() == goals[planResult.selectedGoalIdx].configuration. If there is a planning error, the list is empty.

Returns:

A list of waypoints

Configuration finalConfiguration() const

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().back().configuration. This throws if the path planning failed.

Returns:

The final configuration of the path

explicit operator bool() const

Returns true if there is no planning error, false otherwise.

Makes it convenient to do if(planResult): ...

Public Members

std::optional<Error> error

The PathResult will have an error set if the planner did not find a collision-free path to any of the goals.

std::optional<uint32_t> selectedGoalIdx

If there is a planning error, this is std::nullopt.

Otherwise, this is the index to the selected goal in the goals vector.

Tcp tcp

The TCP when the PathResult was computed.

class Obstacle

Represents an obstacle in the robot environment, to be used with the setObstacles() method.

The obstacle coordinates must be expressed in the cell base frame.

Public Types

using PointCloud = std::vector<PointXYZ>

A vector of points representing a point cloud.

using Colors = std::vector<ColorRGBA>

A vector of colors.

Public Static Functions

static Obstacle fromMesh(std::string name, Triangles mesh)

Initializes an Obstacle instance from a triangle mesh geometry.

static Obstacle fromColoredMesh(std::string name, Triangles mesh, ColorRGBA color)

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.

static Obstacle fromPointCloud(std::string name, PointCloud pointCloud)

Initializes an Obstacle instance from a point cloud.

static Obstacle fromColoredPointCloud(std::string name, PointCloud pointCloud, Colors colors)

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.

class CarriedObject

Represents an object that the robot carries during motion planning, to be used with the setCarriedObject() 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.

Public Static Functions

static CarriedObject fromBox(const TransformedBox &box)

Initializes a CarriedObject instance from a box-shaped geometry.

Parameters:

box – The box geometry with its transform and dimensions.

static CarriedObject fromMesh(const Pose &transform, const Triangles &mesh)

Initializes a CarriedObject instance from a triangle mesh geometry.

Parameters:
  • transform – The transform of the mesh vertices.

  • mesh – The mesh defining the object surface.

class ReplaceableTool

Represents a replaceable tool that can be mounted on the robot flange, to be used with the setReplaceableTool() method.

When the replaceable tool is set on the robot, this geometry is added to the robot’s collision model. The geometry is defined in the robot flange frame.

Public Static Functions

static ReplaceableTool fromBoxElements(const std::vector<ToolBoxElement> &toolElements)

Creates a ReplaceableTool from multiple tool box elements.

The collection of tool elements represents the overall geometry of the replaceable tool.

Parameters:

toolElements – Vector of tool box elements.

struct ToolBoxElement

A tool element representing a rigid box geometry and an optional compliant box geometry.

Public Members

Pose transform

The transformation of the tool element relative to the flange frame.

VectorXYZ rigidBoxDimensions

The bottom centered box dimensions representing the rigid geometry of the tool element.

std::optional<TransformedBox> compliantBox = {}

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

struct Tcp

Represents a tool center point (TCP) of the robot.

It contains the transform and tool direction.

Public Members

Pose transform

The transform of the TCP, relative to the robot flange frame.

VectorXYZ toolDirection

The tool direction of the TCP, expressed in the new TCP frame.

This is used for interaction planning in Touch operations.

enum class Zivid::Motion::Profile

Used to specify a testing or production profile for a robot cell.

Values:

enumerator testing
enumerator production
struct PlannerSettings

Settings to instantiate the Planner.

Public Members

std::string cellName

The identifier for the planner configuration data path.

Profile profile

Used to specify a testing or production profile for a robot cell.

struct TransformedBox

Represents a box with a given transform.

Public Members

Pose bottomCenteredTransform

The transformation from the context-dependent reference frame to the box bottom center.

VectorXYZ dimensions

The dimensions of the box.

struct ColorRGBA

Color with red, green, blue and alpha channels.

struct Vector3f

Vector of three floating point values.


Typedefs

using Zivid::Motion::Configuration = std::vector<float>

Vector holding the joint angles of the robot, expressed in radians.

using Zivid::Motion::Pose = std::array<std::array<float, 4>, 4>

4x4 array representing a homogeneous transformation matrix, such as a robot pose.

The translation part should be expressed in meters.

Each element in the outer array is a row of the 4x4 matrix.

using Zivid::Motion::Path = std::vector<Waypoint>

Vector of waypoints.

using Zivid::Motion::PointXYZ = Vector3f

Point with three coordinates as float, expressed in meters.

using Zivid::Motion::VectorXYZ = Vector3f

Vector with three coordinates as float, expressed in meters.

using Zivid::Motion::Triangle = std::array<PointXYZ, 3>

Array of 3 PointXYZ representing a triangle.

using Zivid::Motion::Triangles = std::vector<Triangle>

Vector of triangles.

using Zivid::Motion::ProgressCallback = std::function<void(double, const std::string&)>

A progress callback function type.

Param progressPercentage:

The progress completion percentage (0 - 100%).

Param updateStageDescription:

A textual description of the progress stage.


Free Functions

void Zivid::Motion::generate(const Application &application, const PlannerSettings &plannerSettings, const ProgressCallback &progressCallback = {})

Generate cell data.

Parameters:
  • application – Motion application

  • plannerSettings – Settings for generation

  • progressCallback – An optional progress callback function

void Zivid::Motion::packageCell(const Application &application, const std::string &cellName, const std::filesystem::path &outputPath, const std::vector<Profile> &includeGeneratedData)

Packages a cell into a zip archive.

This function collects all files required to execute the planner with the specified cell 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.

Parameters:
  • application – Motion application

  • cellName – The name of the cell to package.

  • outputPath – The destination path for the generated zip archive, including the filename with “.zip” extension.

  • includeGeneratedData – What generated data to include.

std::filesystem::path Zivid::Motion::packageApiLog(const Application &application, const std::filesystem::path &apiLogPath)

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:
  • application – Motion application

  • apiLogPath – The path to the API log

Returns:

The path to the created zip archive.

void Zivid::Motion::installPackage(const Application &application, const std::filesystem::path &packagePath)

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.

Parameters:
  • application – Motion application

  • packagePath – The path to the cell package (zip archive) to install.