Motions¶
-
struct LinearSection¶
Represents a linear Cartesian section for either the approach to the goal or the retraction from the start.
Public Types
-
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.
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.
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.
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.
-
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.
-
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).
-
inline explicit Motion(const Point &start, const Point &goal)¶
-
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.
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.
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.
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.
-
inline explicit LinearMotion(const ExactPoint &start, const ExactPoint &goal)¶
-
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.
-
enumerator Position¶
-
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.
-
enumerator Phase¶
-
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.
-
enumerator Continuous¶
Public Functions
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.
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.
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::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.
-
enum ControlInterface¶
Warning
doxygenclass: Cannot find class “jacobi::PathSegment” in doxygen xml output for project “jacobi_motion_library” from directory: ../doxygen_xml/motion/latest
-
class LinearPath : public jacobi::PathSegment¶
-
class CircularPath : public jacobi::PathSegment¶
Public Functions
-
CircularPath(const Frame &start, const double theta, const std::array<double, 3> ¢er, const std::array<double, 3> &normal, bool keep_tool_to_surface_orientation = true)¶
Construct a CircularPath with a given start pose, rotation angle, circle center, and normal.
- 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 an array 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::array<double, 3> ¢er, bool keep_tool_to_surface_orientation = true)¶
Construct a CircularPath with a given start pose, goal pose, and circle center. 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 an array of doubles.
keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.
-
CircularPath() = default¶
Default constructor.
Public Members
-
double theta¶
The rotation angle of the circular path [rad].
-
std::array<double, 3> center¶
The center of the circle.
-
std::array<double, 3> 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.
-
CircularPath(const Frame &start, const double theta, const std::array<double, 3> ¢er, const std::array<double, 3> &normal, bool keep_tool_to_surface_orientation = true)¶
-
class Path¶
Abstract base class representing a type of path.
The PathType class provides an abstract interface for different types of paths.
Public Functions
-
Path() = default¶
Default constructor.
Construct a path from a linear segment.
- Parameters:
segment – The linear segment defining the path.
Construct a path from a circular segment.
- Parameters:
segment – The circular segment defining the path.
-
inline std::vector<std::shared_ptr<const PathSegment>> get_segments() const¶
Get the individual segments of the path.
-
inline double get_length() const¶
Get the overall length of the path.
-
Frame position(double s) const¶
Calculate the position at the path parameter s.
- Parameters:
s – The path parameter (0.0 to length).
-
std::vector<Frame> sample_positions(const double velocity, const double delta_time)¶
Sample positions along the path with a given constant velocity and time step.
- Parameters:
velocity – The constant velocity of the end-effector [m/s].
delta_time – The time step for sampling the path [s].
- Returns:
std::vector<Frame> The sampled positions along the path.
Public Static Functions
-
static Path from_waypoints(const std::vector<Frame> &waypoints, const std::optional<double> &blend_radius = std::nullopt, bool keep_tool_to_surface_orientation = true)¶
Construct a path from a list of waypoints and a blend radius.
- 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.
-
Path() = default¶
-
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 currently three different path types that are supported: linear, circular and blended. 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(const Path &path, const double velocity = 50.0)¶
Construct a PathFollowingMotion with a given path type and optional velocity.
- Parameters:
path – 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, const Path &path, 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 – 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.
Construct a PathFollowingMotion with a robot, path type, and optional velocity.
- Parameters:
robot – The robot for the motion.
path – 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.
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.
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).
-
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).
-
inline explicit PathFollowingMotion(const Path &path, const double velocity = 50.0)¶
-
class BimanualMotion¶
Represents a request for a collision-free point-to-point bimanual motion for dual-arm robots.
The BimanualMotion class provides an interface for general point-to-point motion planning for dual-arm robots 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 intermediate waypoints, setting if the bimanual motion should be coordinated, and soft failure handling.
Public Functions
Construct a BimanualMotion with left and right robot arms, start and goal point.
- Parameters:
arm_left – The left robot arm for the motion.
arm_right – The right robot arm for the motion.
start – The start point of the motion.
goal – The goal point of the motion.
Construct a BimanualMotion with a name, left and right robot arms, start and goal point.
- Parameters:
name – The unique name of the motion.
arm_left – The left robot arm for the motion.
arm_right – The right robot arm for the motion.
start – The start point of the motion.
goal – The goal point of the motion.
Construct a BimanualMotion with a robot, start and goal point.
- Parameters:
robot – The dual-arm robot for the motion.
start – The start point of the motion.
goal – The goal point of the motion.
Construct a BimanualMotion with a name, robot, start and goal point.
- Parameters:
name – The unique name of the motion.
robot – The dual-arm robot for the motion.
start – The start point of the motion.
goal – The goal point of the motion.
-
inline explicit BimanualMotion()¶
Default constructor.
Public Members
-
std::string name¶
The unique name of the bimanual motion.
-
std::shared_ptr<DualArm> robot¶
The dual-arm robot for the bimanual motion (e.g. defines the kinematics and the joint limits).
-
MultiRobotPoint start¶
Start point of the motion for both arms.
-
MultiRobotPoint goal¶
Goal point of the motion for both arms.
-
bool is_coordinated = {false}¶
Flag to indicate if the motion is coordinated, in which case the follower arm moves with a constant offset to the leader arm.
-
std::shared_ptr<RobotArm> leader_arm¶
The leader arm for the coordinated motion. Left arm is used by default if this variable is not set.
-
std::vector<MultiRobotPoint> waypoints¶
Intermediate waypoints for both arms that the motion passes through exactly. The list of waypoints is limited to less than four.
-
std::optional<MultiRobotLinearSection> linear_retraction¶
Optional relative linear cartesian motion for retracting from the start pose, specified for one or both arms.
-
std::optional<MultiRobotLinearSection> linear_approach¶
Optional relative linear cartesian motion for approaching the goal pose, specified for one or both arms.