Motions#

class LinearSection

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

Frame offset

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

double speed = 1.0

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

LinearSection::Approximation approximation = LinearSection.Approximation.Always

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

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.

std::string name

The unique name of the motion.

Point start

Start point of the motion.

Point goal

Goal point of the motion.

std::vector<Point> 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::shared_ptr<Robot> robot

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

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.

double 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)

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

Represents a request for a linear Cartesian-space motion.

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

LinearMotion(const std::string &name, std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)
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.

enum ControlInterface
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
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
enumerator Continuous

Every trajectory synchronization duration is allowed. (Default)

enumerator Discrete

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

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 point of the motion.

Waypoint goal

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

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