Motions

struct LinearSection

Represents a linear Cartesian section for either the approach to the goal or the retraction from the start.

Public Types

enum class Approximation

Whether to approximate the Cartesian linear motion in joint space for singularity-free calculation.

Values:

enumerator Never
enumerator Always

Public Members

Frame offset

Relative linear cartesian offset from the reference pose.

double speed = {1.0}

Speed of the sub-motion, relative to the overall motion’s speed.

bool smooth_transition = {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.

The Motion class provides an interface for general point-to-point motion planning with arbitrary waypoints, linear approach and retraction, and task constraints. It includes parameters for the motion name, robot, start and goal points, and additional settings for motion planning, such as collision checking and soft failure handling.

Public Functions

inline explicit Motion(const Point &start, const Point &goal)

Construct a Motion with a given start and goal point.

Parameters:
  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion(std::shared_ptr<Robot> robot, const Point &start, const Point &goal)

Construct a Motion with a name, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion(const std::string &name, const Point &start, const Point &goal)

Construct a Motion with a name, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

explicit Motion(const std::string &name, std::shared_ptr<Robot> robot, const Point &start, const Point &goal)

Construct a Motion with a name, robot, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm associated with the motion.

bool is_within(std::shared_ptr<Robot> robot, const Waypoint &start_test, const Waypoint &goal_test) const

Check if the motion start and goal points are within the provided start and goal points.

Parameters:
  • start_test – The start point to compare against.

  • goal_test – The goal point to compare against.

Returns:

true If the motion start and goal points are within the provided start and goal points.

Returns:

false If the motion start and goal points are not within the provided start and goal points.

Public Members

std::string name

The unique name of the motion.

Point start

Start point of the motion.

Point goal

Goal point of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

bool ignore_collisions = {false}

Whether to ignore collisions.

std::vector<ExactPoint> waypoints

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.

std::optional<LinearSection> linear_retraction

Optional relative linear cartesian motion for retracting from the start pose.

std::optional<LinearSection> linear_approach

Optional relative linear cartesian motion for approaching the goal pose.

bool soft_collision_start = {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.

bool soft_collision_goal = {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.

double path_length_loss_weight = {0.1}

Weight of the loss minimizing the path length of the trajectory.

double orientation_loss_weight = {0.0}

Weight of the loss minimizing the maximizing deviation of the end-effector orientation to the target value.

std::array<double, 3> orientation_target = {{0.0, 0.0, 1.0}}

Target vector pointing in the direction of the end-effector (TCP) orientation in the global coordinate system.

std::optional<double> cartesian_tcp_speed_cutoff

Optional Cartesian TCP speed (translation-only) cutoff. This is a post-processing step.

std::optional<std::vector<ExactPoint>> initial_waypoints

Optional initial waypoints to start the optimization with (don’t use with intermediate waypoints).

class LinearMotion

Represents a request for a linear Cartesian-space motion.

The LinearMotion struct represents a request for a linear motion in Cartesian space. It consists of a start and goal point, as well as a robot to perform the motion. It provides an interface for planning singularity-free linear motion in Cartesian space between any two waypoints.

Public Functions

inline explicit LinearMotion(const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given start, and goal.

Parameters:
  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion(std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given robot, start, and goal.

Parameters:
  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion(const std::string &name, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given name, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

explicit LinearMotion(const std::string &name, std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given name, robot, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm for the motion.

Public Members

std::string name

The unique name of the motion.

ExactPoint start

Start point of the motion.

ExactPoint goal

Goal point of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

bool ignore_collisions = {true}

Whether to ignore collisions.

class LowLevelMotion

Represents a request for a low-level motion.

The LinearMotion class provides an interface for very efficient planning of motion between joint-space waypoints. 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. This motion type is suitable for visual servoing task or other real-time control.

Public Types

enum ControlInterface

The control interface for the motion, specifying either position or velocity control.

Values:

enumerator Position

Position-control: Full control over the entire kinematic state (Default)

enumerator Velocity

Velocity-control: Ignores the current position, target position, and velocity limits.

enum Synchronization

The synchronization strategy for the motion, specifying either phase, time, time if necessary, or no synchronization.

Values:

enumerator Phase

Phase synchronize the DoFs when possible, else fallback to “Time” strategy (Default)

enumerator Time

Always synchronize the DoFs to reach the target at the same time.

enumerator TimeIfNecessary

Synchronize only when necessary (e.g. for non-zero target velocity or acceleration)

enumerator None

Calculate every DoF independently.

enum DurationDiscretization

The duration discretization strategy for the motion, specifying either continuous or discrete durations.

Values:

enumerator Continuous

Every trajectory synchronization duration is allowed (Default)

enumerator Discrete

The trajectory synchronization duration must be a multiple of the control cycle.

Public Functions

inline explicit LowLevelMotion(std::shared_ptr<Robot> robot)

Construct a low-level motion with a given robot.

Parameters:

robot – The robot for the motion.

inline explicit LowLevelMotion(const std::string &name)

Construct a low-level motion with a given name.

Parameters:

name – The unique name of the motion.

explicit LowLevelMotion(const std::string &name, std::shared_ptr<Robot> robot)

Construct a low-level motion with a given name, robot, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

inline explicit LowLevelMotion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm for the motion.

Public Members

std::string name

The unique name of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

Waypoint start

Start waypoint of the motion.

Waypoint goal

Goal waypoint of the motion.

std::vector<Config> intermediate_positions

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.

std::optional<double> minimum_duration

A minimum duration of the motion.

ControlInterface control_interface = {ControlInterface::Position}

The control interface for the motion.

Synchronization synchronization = {Synchronization::Phase}

The synchronization strategy for the motion.

DurationDiscretization duration_discretization = {DurationDiscretization::Continuous}

The duration discretization strategy for the motion.

class LinearPath : public jacobi::PathType

A path type for linear motion between two waypoints.

The LinearPath class implements the PathType interface to represent a linear path from a start pose to a goal pose. It calculates waypoints along a straight line between the two poses and supports serialization and deserialization to/from JSON.

Public Functions

inline LinearPath(const Frame &start, const Frame &goal)

Construct a LinearPath with a given start and goal pose.

Parameters:
  • start – The starting pose of the linear path.

  • goal – The ending pose of the linear path.

inline LinearPath()

Default constructor.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints for the linear motion.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

virtual bool operator!=(const PathType &rhs) const override

Compare two PathType objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the objects are not equal.

Returns:

false If the objects are equal.

Public Members

Frame start

The start pose of the linear path.

Frame goal

The goal pose of the linear path.

class CircularPath : public jacobi::PathType

A circular path type with a specified start pose, circle center, normal, and rotation angle, optionally maintaining tool-to-surface orientation.

The CircularPath class implements the PathType interface to represent a circular path with a given start pose, circle center, normal to the plane of the circle, and rotation angle. This path type optionally supports maintaining tool-to-surface orientation throughout the path.

Public Functions

inline CircularPath(const Frame &start, const double theta, const std::vector<double> &center, const std::vector<double> &normal, const bool keep_tool_to_surface_orientation = false)

Construct a CircularPath with a given start pose, rotation angle, circle center, normal, and optional tool-to-surface orientation.

Parameters:
  • start – The starting pose of the circular path.

  • theta – The rotation angle of the circular path in radians.

  • center – The center of the circle as a vector of doubles.

  • normal – The normal vector of the plane containing the circle.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

CircularPath(const Frame &start, const Frame &goal, const std::vector<double> &center, const bool keep_tool_to_surface_orientation = false)

Construct a CircularPath with a given start pose, goal pose, circle center, and optional tool-to-surface orientation. The rotation angle is inferred from the goal pose.

Parameters:
  • start – The starting pose of the circular path.

  • goal – The goal pose of the circular path (used to infer theta).

  • center – The center of the circle as a vector of doubles.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

inline CircularPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two CircularPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the CircularPath object is not equal to the provided PathType object.

Returns:

false If the CircularPath object is equal to the provided PathType object.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints for the circular motion.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

Public Members

Frame start

The start pose of the circular path.

double theta

The rotation angle of the circular path [rad].

std::vector<double> center

The center of the circle.

std::vector<double> normal

The normal of the plane in which to create a circular path.

bool keep_tool_to_surface_orientation

Whether to maintain the tool-to-surface orientation.

class BlendedPath : public jacobi::PathType

A path type for linear motion between waypoints with a circular blend to ensure motion continuity, optionally maintaining tool-to-surface orientation.

The BlendedPath class implements the PathType interface to represent a path that smoothly transitions between Cartesian waypoints with circular blends. This ensures continuity of motion. This path type optionally supports maintaining tool-to-surface orientation throughout the path.

Public Functions

inline BlendedPath(const PathWaypoints &waypoints, const double blend_radius, const bool keep_tool_to_surface_orientation = false)

Construct a BlendedPath with given waypoints, blend radius, and optional tool-to-surface orientation.

Parameters:
  • waypoints – The Cartesian waypoints defining the path.

  • blend_radius – The radius for the circular blend between waypoints.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

BlendedPath(const PathWaypoints &waypoints, const bool keep_tool_to_surface_orientation = false)

Construct a BlendedPath with given waypoints and optional tool-to-surface orientation. The blend radius is automatically calculated.

Parameters:
  • waypoints – The Cartesian waypoints defining the path.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

inline BlendedPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two BlendedPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the BlendedPath object is not equal to the provided PathType object.

Returns:

false If the BlendedPath object is equal to the provided PathType object.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints with piecewise linear motion and circular blends.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

Public Members

PathWaypoints waypoints

The path Cartesian waypoints.

double blend_radius

The blend radius for the circular blend.

bool keep_tool_to_surface_orientation

Whether to maintain the tool-to-surface orientation.

class ArbitraryPath : public jacobi::PathType

A wrapper for a path with arbitrary user-provided waypoints.

The ArbitraryPath class implements the PathType interface and serves as a wrapper for a path defined by user-provided Cartesian waypoints. This class allows users to specify their own sequence of waypoints directly, without additional path calculations.

Public Functions

inline ArbitraryPath(const PathWaypoints &path)

Construct an ArbitraryPath with given waypoints.

Parameters:

path – The Cartesian waypoints defining the path.

inline ArbitraryPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two ArbitraryPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the ArbitraryPath object is not equal to the provided PathType object.

Returns:

false If the ArbitraryPath object is equal to the provided PathType object.

inline virtual PathWaypoints calculate_path(const double, const double) override

Return the user-provided waypoints as the calculated path.

Parameters:
  • velocity – The velocity used for path calculation (not utilized in this case).

  • delta_time – The time step used for path calculation (not utilized in this case).

Returns:

The waypoints provided by the user as the path.

Public Members

PathWaypoints path

The path Cartesian waypoints.

class PathFollowingMotion

Represents a request for a Cartesian-space motion to be followed by the end-effector.

The PathFollowingMotion class provides an interface for Cartesian-space paths to be accurately followed by the robot end-effector with a constant velocity. There are four different path types that are supported: linear, circular, blended and arbitrary. The path-following motion is suitable for use cases such as welding, painting, dispensing and deburring, where constant end-effector velocity is required for successful task execution. It includes parameters for the motion name, robot, path type, velocity, and additional settings for motion planning, such as collision checking and soft failure handling.

Public Functions

inline explicit PathFollowingMotion(std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a given path type and optional velocity.

Parameters:
  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline explicit PathFollowingMotion(const std::string &name, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a name, path type, and optional velocity.

Parameters:
  • name – The unique name of the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline explicit PathFollowingMotion(std::shared_ptr<Robot> robot, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a robot, path type, and optional velocity.

Parameters:
  • robot – The robot for the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

explicit PathFollowingMotion(const std::string &name, std::shared_ptr<Robot> robot, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a name, robot, path type, and optional velocity.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline PathFollowingMotion()

Default constructor.

inline PathWaypoints calculate_path(const double delta_time)

Calculate the path waypoints based on the current feasible velocity and delta time.

Parameters:

delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

bool operator!=(const PathFollowingMotion &rhs) const

Compare two PathFollowingMotion objects for inequality.

Parameters:

rhs – The PathFollowingMotion object to compare against.

Returns:

true If the objects are not equal.

Returns:

false If the objects are equal.

Public Members

std::string name

The unique name of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

std::shared_ptr<PathType> path_type

The Cartesian path to follow.

double velocity = {50.0}

The desired velocity of the end-effector [m/s].

bool soft_failure = {true}

If true, the planner will adjust path velocity until a solution until velocity limits are satisfied.

bool check_collision = {true}

If true, the planner will check for collisions during the motion.

std::optional<Config> reference_config

Optional reference configuration for the start state of the motion.

double feasible_velocity = {50.0}

The feasible velocity of the end-effector achieved after planning [m/s] (only used if soft_failure is true).