C++ API Reference
-
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.
-
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.
-
float entry
-
struct ColorRGBA
Color with red, green, blue and alpha channels
-
struct GenerationSettingsData
Settings to pass to generate
Public Types
Public Members
-
std::string dataTag
The identifier for the planner configuration data path
-
GenerateConfig generateConfig = GenerateConfig::testing
Selects which config to generate for
-
std::string dataTag
-
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
- explicit (false) 1 InitialState(const Configuration &startConfiguration)
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.
- Parameters:
startConfiguration – The robot’s start configuration for the path planning
- explicit (false) 1 InitialState(const PlanResult &previousResult)
Initializes the InitialState from a PlanResult
This overload is intended for consecutive robot motions. It requires that the provided PlanResult has status Success.
- Parameters:
previousResult – A previous successful PlanResult
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 plan result is not available. For consecutive motions, it is recommended to use the PlanResult constructor.
- Parameters:
startConfiguration – The robot’s start configuration for the path planning in touch
-
struct Obstacle
Represents an obstacle in the robot environment, to be used with the setObstacles() method.
It can be constructed from four different data types: PointCloud, ColoredPointCloud, Triangles or ColoredTriangles.
Important: Colored obstacles impact performance. Avoid using them in production.
-
struct PathSettingsData
Settings to pass to a path call
Public Types
-
enum class Type
Used to specify the motion type
Values:
-
enumerator free
(Default) For moving in free space.
-
enumerator 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.
-
enumerator free
-
enum class GoalPrioritizationMethod
Used to specify the goal prioritization method
Values:
-
enumerator listOrder
(Default) 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.
-
enumerator listOrder
Public Members
-
GoalPrioritizationMethod goalPrioritizationMethod = GoalPrioritizationMethod::listOrder
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.
-
enum class Type
-
class Planner : private Zivid::Motion::Traits::NoCopy
Public Functions
-
explicit Planner(const PlannerSettingsData &plannerSettings)
Initializes a Planner instance from planner settings
- Parameters:
plannerSettings – Planner settings data
-
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.
-
PlanResult path(const InitialState &initialState, const std::vector<Configuration> &goalConfigurations, const PathSettingsData &pathSettings = PathSettingsData{}, const std::optional<std::string> &description = std::nullopt) const
Calculates a path to one of multiple goal configurations from the initial state
- Parameters:
initialState – The initial state for the path (created from a start configuration or a plan result)
goalConfigurations – Goal configurations
pathSettings – Settings for the path call
description – Description can be used to easily distinguish between path calls in the visualizer
-
std::vector<bool> checkMeshCollisions(const std::vector<Configuration> &configurations, unsigned int numIgnoredLinksFromTip) const
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 numIgnoredLinksFromTip 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 numIgnoredLinksFromTip > 0.
Also note that including multiple configurations in the same call is faster than iterative calls to this method.
- Parameters:
configurations – Configurations
numIgnoredLinksFromTip – Number of ignored links from tip
- Returns:
One bool per input configuration. True if the configuration is in collision, False otherwise.
-
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.
The obstacle coordinates must be expressed in the base frame of the planner and given in millimeters. 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 – Obstacles
-
void clearObstacles() const
Clears all registered obstacles from the planner’s collision model
-
void setCarriedObject(const Pose &transform, const VectorXYZ &boxDimensions) const
Updates the robot’s collision model with a bounding box of the object it’s now holding
- Parameters:
transform – 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.
boxDimensions – Dimensions of the bounding box in the x, y and z direction of the transformed TCP frame. This should be specified in millimeters.
-
void setCarriedObject(const Pose &transform, const Triangles &triangles) const
Updates the robot’s collision model with a mesh of the object it’s now holding
- Parameters:
transform – Transform is a transformation from the current TCP frame to mesh triangles. The translation is applied in the TCP frame (not the final rotated frame) and should be specified in millimeters.
triangles – Triangles specifying the mesh of the carried object. This should be specified in millimeters.
-
void clearCarriedObject() const
Clears the carried object from the robot’s collision model
-
void setReplaceableTool(const Pose &transform, const VectorXYZ &boxDimensions) const
Updates the robot’s collision model with a bounding box of the current configuration of a modifyable or exchangeable end-effector tool
- Parameters:
transform – 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.
boxDimensions – BoxDimensions is the dimensions of the bounding box in the x, y and z direction of the transformed reference frame. This should be specified in millimeters.
-
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 set
-
void clipPointCloud(const Pose &bottomCenterTransform, const VectorXYZ &boxDimensions)
Updates the environment point cloud by removing all points inside the specified box.
- Parameters:
bottomCenterTransform – The transformation from the cell base frame to the bottom center position of the bounding box. The translation should be specified in millimeters.
boxDimensions – The dimensions of the bounding box. This should be specified in millimeters.
-
void clipPointCloud(const Pose &transform, const Triangles &triangles)
Updates the environment point cloud by removing all points inside the specified mesh triangles.
- Parameters:
transform – The transformation from the cell base frame to the mesh triangles. The translation should be specified in millimeters.
triangles – The triangles specifying the mesh. This should be specified in millimeters. 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.
-
explicit Planner(const PlannerSettingsData &plannerSettings)
-
class PlanResult
PlanResult is the result of calculating a path to a set of potential goals.
It’s the return value from Planner.path().
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, meaning: path[-1].configuration == goals[executed_goal_id].configuration). If status != Status.success the list is empty.
- Returns:
A list of waypoints
-
Configuration finalConfiguration() const
Returns the final configuration of the robot after executing the path
This performs the same operation as calling path().back().configuration,
- Returns:
The final configuration of the path
-
explicit operator bool() const
Returns true if status == Status.success, false otherwise
Public Members
-
Status 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.
-
std::optional<uint32_t> selectedGoalIdx
If status == Status.success, this is the index to the selected goal in the goals vector.
If status != Status.success, this is std::nullopt.
-
Tcp tcp
The TCP when the PlanResult was computed
-
Path path() const
-
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
Transform is the transformation from the robot flange frame defined in your config 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.
-
VectorXYZ toolDirection
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.
-
Pose transform
-
struct Vector3f
Vector of three floating point values
-
struct Waypoint
A waypoint in joint space, describing where and how the robot should move as part of a path
Public Members
-
Configuration configuration
The joint configuration of the waypoint
-
Movement 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).
-
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 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.
-
Configuration configuration
-
Triangles Zivid::Motion::createBoxMesh(const PointXYZ ¢erPoint, const VectorXYZ &size)
Create a mesh representing an axis-aligned rectangular cuboid.
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:
centerPoint – Center point
size – Size
- Returns:
A list of triangles that represent a box mesh
-
void Zivid::Motion::generate(const GenerationSettingsData &generationSettings, const ProgressCallback &progressCallBack = {})
Generate cell data
- Parameters:
generationSettings – Generation settings
progressCallBack – An optional progress callback function
-
void Zivid::Motion::packageDataTag(const std::string &dataTag, const std::filesystem::path &outputPath, const std::vector<std::string> &includeGeneratedData)
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:
dataTag – The name of the data tag to package.
outputPath – The destination path for the generated zip archive.
includeGeneratedData – What generated data to include (Testing/Production).
-
std::filesystem::path Zivid::Motion::packageApiLog(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.zipsuffix instead of the.jsonextension. The API log itself is not packaged.- Parameters:
apiLogPath – The path to the API log
- Returns:
The path to the created zip archive.
-
void Zivid::Motion::installPackage(const std::filesystem::path &packagePath)
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:
packagePath – The path to the data tag package (zip archive) to install.
Typedefs
-
using Zivid::Motion::Configuration = std::vector<float>
Vector representing joint configuration
-
using Zivid::Motion::Pose = std::array<std::array<float, 4>, 4>
Array representing robot pose
-
using Zivid::Motion::Triangle = std::array<PointXYZ, 3>
Array of 3 PointXYZ representing a triangle
-
using Zivid::Motion::ColoredTriangles = std::pair<Triangles, ColorRGBA>
Pair of Triangle vectors and ColorRGBA representing colored 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.