Motions

class LinearSection

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

offset: Frame

Relative linear cartesian offset from either the start of the goal.

speed: float = 1.0

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

approximation: LinearSection.Approximation = LinearSection.Approximation.Always

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

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

name: str

The unique name of the motion.

start: Point

Start point of the motion.

goal: Point

Goal point of the motion.

waypoints: List[Point]

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.

robot: Robot

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

linear_retraction: LinearSection | None

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

linear_approach: LinearSection | None

Optional relative linear cartesian motion for approaching the goal pose.

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

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

path_length_loss_weight: float = 0.1

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

orientation_loss_weight: float = 0.0

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

orientation_target: List[float] = [0.0, 0.0, 1.0]

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

cartesian_tcp_speed_cutoff: float | None

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

initial_waypoints: List[ExactPoint] | None

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

__init__(name: str, robot: Robot, start, goal)
class LinearMotion

Represents a request for a linear Cartesian-space motion.

name: str

The unique name of the motion.

start: Point

Start point of the motion.

goal: Point

Goal point of the motion.

robot: Robot

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

__init__(name: str, robot: Robot, start: ExactPoint, goal: ExactPoint)
class LowLevelMotion

Represents a request for a low-level motion. 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.

class ControlInterface
Position

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

Velocity

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

class Synchronization
Phase

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

Time

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

TimeIfNecessary

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

None

Calculate every DoF independently.

class DurationDiscretization
Continuous

Every trajectory synchronization duration is allowed. (Default)

Discrete

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

name: str

The unique name of the motion.

robot: Robot

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

start: Waypoint

Start point of the motion.

goal: Waypoint

Goal point of the motion.

intermediate_positions: List[Config]

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.

minimum_duration: float | None

A minimum duration of the motion.

control_interface: ControlInterface = ControlInterface.Position

The control interface for the motion.

synchronization: Synchronization = Synchronization.Phase

The synchronization strategy for the motion.

duration_discretization: DurationDiscretization = DurationDiscretization.Continuous

The duration discretization strategy for the motion.

__init__(name: str, robot: Robot)