MotionsΒΆ
- class jacobi.LinearSectionΒΆ
Bases:
pybind11_object
Represents a linear Cartesian section for either the approach to the goal or the retraction from the start.
- class ApproximationΒΆ
Bases:
pybind11_object
Whether to approximate the Cartesian linear motion in joint space for singularity-free calculation.
Members:
Always :
Never :
- __init__(self: Approximation, value: int) None ΒΆ
- property nameΒΆ
- __init__(self: jacobi.LinearSection, offset: jacobi.Frame, speed: float = 1.0, approximation: jacobi.LinearSection.Approximation = <Approximation.Never: 0>, smooth_transition: bool = True) None ΒΆ
- property offsetΒΆ
Relative linear cartesian offset from the reference pose.
- property smooth_transitionΒΆ
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.
- property speedΒΆ
Speed of the sub-motion, relative to the overall motionβs speed.
- class jacobi.MotionΒΆ
Bases:
pybind11_object
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.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.Motion, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion]) -> None
Construct a Motion with a given start and goal point.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.Motion, robot: jacobi.Robot, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion]) -> None
Construct a Motion with a name, start and goal point.
- Parameter
name
: The unique name of the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.Motion, name: str, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion]) -> None
Construct a Motion with a name, start and goal point.
- Parameter
name
: The unique name of the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.Motion, name: str, robot: jacobi.Robot, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint, jacobi.Region, jacobi.CartesianRegion]) -> None
Construct a Motion with a name, robot, start and goal point.
- Parameter
name
: The unique name of the motion.
- Parameter
robot
: The robot for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
- property cartesian_tcp_speed_cutoffΒΆ
Optional Cartesian TCP speed (translation-only) cutoff. This is a post-processing step.
- property goalΒΆ
Goal point of the motion
- property ignore_collisionsΒΆ
Whether to ignore collisions
- property initial_waypointsΒΆ
Optional initial waypoints to start the optimization with (donβt use with intermediate waypoints).
- property linear_approachΒΆ
Optional relative linear cartesian motion for approaching the goal pose.
- property linear_retractionΒΆ
Optional relative linear cartesian motion for retracting from the start pose.
- property nameΒΆ
The unique name of the motion.
- property orientation_loss_weightΒΆ
Weight of the loss minimizing the maximizing deviation of the end- effector orientation to the target value.
- property orientation_targetΒΆ
Target vector pointing in the direction of the end-effector (TCP) orientation in the global coordinate system.
- property path_length_loss_weightΒΆ
Weight of the loss minimizing the path length of the trajectory.
- property robotΒΆ
The robot for the motion (e.g. defines the kinematics and the joint limits).
- property startΒΆ
Start point of the motion
- property 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.
- class jacobi.LinearMotionΒΆ
Bases:
pybind11_object
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.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.LinearMotion, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]) -> None
Construct a linear motion with a given start, and goal.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.LinearMotion, robot: jacobi.Robot, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]) -> None
Construct a linear motion with a given robot, start, and goal.
- Parameter
robot
: The robot for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.LinearMotion, name: str, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]) -> None
Construct a linear motion with a given name, start, and goal.
- Parameter
name
: The unique name of the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.LinearMotion, name: str, robot: jacobi.Robot, start: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint], goal: Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]) -> None
Construct a linear motion with a given name, robot, start, and goal.
- Parameter
name
: The unique name of the motion.
- Parameter
robot
: The robot for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
- property goalΒΆ
Goal point of the motion.
- property ignore_collisionsΒΆ
Whether to ignore collisions
- property nameΒΆ
The unique name of the motion.
- property robotΒΆ
The robot for the motion (e.g. defines the kinematics and the joint limits).
- property startΒΆ
Start point of the motion
- class jacobi.LowLevelMotionΒΆ
Bases:
pybind11_object
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.
- class ControlInterfaceΒΆ
Bases:
pybind11_object
The control interface for the motion, specifying either position or velocity control.
Members:
Position : Position-control: Full control over the entire kinematic state
(Default)
Velocity : Velocity-control: Ignores the current position, target position, and
velocity limits
- __init__(self: ControlInterface, value: int) None ΒΆ
- property nameΒΆ
- class DurationDiscretizationΒΆ
Bases:
pybind11_object
The duration discretization strategy for the motion, specifying either continuous or discrete durations.
Members:
Continuous : Every trajectory synchronization duration is allowed (Default)
Discrete : The trajectory synchronization duration must be a multiple of the
control cycle
- __init__(self: DurationDiscretization, value: int) None ΒΆ
- property nameΒΆ
- class SynchronizationΒΆ
Bases:
pybind11_object
The synchronization strategy for the motion, specifying either phase, time, time if necessary, or no synchronization.
Members:
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
- __init__(self: Synchronization, value: int) None ΒΆ
- property nameΒΆ
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.LowLevelMotion, robot: jacobi.Robot) -> None
Construct a low-level motion with a given robot.
- Parameter
robot
: The robot for the motion.
__init__(self: jacobi.LowLevelMotion, name: str) -> None
Construct a low-level motion with a given name.
- Parameter
name
: The unique name of the motion.
__init__(self: jacobi.LowLevelMotion, name: str, robot: jacobi.Robot) -> None
Construct a low-level motion with a given name, robot, start, and goal.
- Parameter
name
: The unique name of the motion.
- Parameter
robot
: The robot for the motion.
__init__(self: jacobi.LowLevelMotion) -> None
Default constructor.
- property control_interfaceΒΆ
The control interface for the motion.
- property duration_discretizationΒΆ
The duration discretization strategy for the motion.
- property goalΒΆ
Goal waypoint of the motion.
- property 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.
- property minimum_durationΒΆ
A minimum duration of the motion.
- property nameΒΆ
The unique name of the motion.
- property robotΒΆ
The robot for the motion (e.g. defines the kinematics and the joint limits).
- property startΒΆ
Start waypoint of the motion.
- property synchronizationΒΆ
The synchronization strategy for the motion.
- class jacobi.LinearPathΒΆ
Bases:
pybind11_object
- __init__(self: LinearPath, start: Frame, goal: Frame) None ΒΆ
Construct a LinearPath with a given start and goal pose.
- Parameter
start
: The starting pose of the linear path.
- Parameter
goal
: The ending pose of the linear path.
- Parameter
- property goalΒΆ
The goal pose of the linear path.
- property startΒΆ
The start pose of the linear path.
- class jacobi.CircularPathΒΆ
Bases:
pybind11_object
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.CircularPath, start: jacobi.Frame, theta: float, center: Annotated[list[float], FixedSize(3)], normal: Annotated[list[float], FixedSize(3)], keep_tool_to_surface_orientation: bool = True) -> None
__init__(self: jacobi.CircularPath, start: jacobi.Frame, goal: jacobi.Frame, center: Annotated[list[float], FixedSize(3)], keep_tool_to_surface_orientation: bool = True) -> None
- property centerΒΆ
The center of the circle.
- property keep_tool_to_surface_orientationΒΆ
Whether to maintain the tool-to-surface orientation.
- property normalΒΆ
The normal of the plane in which to create a circular path.
- property startΒΆ
The start pose of the circular path.
- property thetaΒΆ
The rotation angle of the circular path [rad].
- class jacobi.PathΒΆ
Bases:
pybind11_object
Abstract base class representing a type of path.
The PathType class provides an abstract interface for different types of paths.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.Path) -> None
Default constructor
__init__(self: jacobi.Path, arg0: jacobi.LinearPath) -> None
__init__(self: jacobi.Path, arg0: jacobi.CircularPath) -> None
- static from_waypoints(waypoints: list[Frame], blend_radius: float | None = None, keep_tool_to_surface_orientation: bool = True) Path ΒΆ
Construct a path from a list of waypoints and a blend radius
- Parameter
waypoints
: The Cartesian waypoints defining the path.
- Parameter
blend_radius
: The radius for the circular blend between waypoints.
- Parameter
keep_tool_to_surface_orientation
: Whether to maintain tool-to-surface orientation.
- Parameter
- position(self: Path, s: float) Frame ΒΆ
Calculate the position at the path parameter s
- Parameter
s
: The path parameter (0.0 to length).
- Parameter
- sample_positions(self: Path, velocity: float, delta_time: float) list[Frame] ΒΆ
Sample positions along the path with a given constant velocity and time step
- Parameter
velocity
: The constant velocity of the end-effector [m/s].
- Parameter
delta_time
: The time step for sampling the path [s].
- Returns:
std::vector<Frame> The sampled positions along the path.
- Parameter
- property lengthΒΆ
Get the overall length of the path
- property segmentsΒΆ
Get the individual segments of the path
- class jacobi.PathFollowingMotionΒΆ
Bases:
pybind11_object
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.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.PathFollowingMotion, path: jacobi.Path, velocity: float = 50.0) -> None
Construct a PathFollowingMotion with a given path type and optional velocity.
- Parameter
path
: The Cartesian path type to follow.
- Parameter
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.
__init__(self: jacobi.PathFollowingMotion, name: str, path: jacobi.Path, velocity: float = 50.0) -> None
Construct a PathFollowingMotion with a name, path type, and optional velocity.
- Parameter
name
: The unique name of the motion.
- Parameter
path
: The Cartesian path type to follow.
- Parameter
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.
__init__(self: jacobi.PathFollowingMotion, robot: jacobi.Robot, path: jacobi.Path, velocity: float = 50.0) -> None
Construct a PathFollowingMotion with a robot, path type, and optional velocity.
- Parameter
robot
: The robot for the motion.
- Parameter
path
: The Cartesian path type to follow.
- Parameter
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.
__init__(self: jacobi.PathFollowingMotion, name: str, robot: jacobi.Robot, path: jacobi.Path, velocity: float = 50.0) -> None
Construct a PathFollowingMotion with a name, robot, path type, and optional velocity.
- Parameter
name
: The unique name of the motion.
- Parameter
robot
: The robot for the motion.
- Parameter
path_type
: The Cartesian path type to follow.
- Parameter
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.
- robot_arm(self: PathFollowingMotion) RobotArm ΒΆ
- property check_collisionΒΆ
If true, the planner will check for collisions during the motion.
- property feasible_velocityΒΆ
The feasible velocity of the end-effector achieved after planning [m/s] (only used if soft_failure is true).
- property nameΒΆ
The unique name of the motion.
- property pathΒΆ
The Cartesian path to follow.
- property reference_configΒΆ
Optional reference configuration for the start state of the motion.
- property robotΒΆ
The robot for the motion (e.g. defines the kinematics and the joint limits).
- property soft_failureΒΆ
If true, the planner will adjust path velocity until a solution until velocity limits are satisfied.
- property velocityΒΆ
The desired velocity of the end-effector [m/s].
- class jacobi.BimanualMotionΒΆ
Bases:
pybind11_object
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.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.BimanualMotion, arm_left: jacobi.RobotArm, arm_right: jacobi.RobotArm, start: jacobi.MultiRobotPoint, goal: jacobi.MultiRobotPoint) -> None
Construct a BimanualMotion with left and right robot arms, start and goal point.
- Parameter
arm_left
: The left robot arm for the motion.
- Parameter
arm_right
: The right robot arm for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.BimanualMotion, name: str, arm_left: jacobi.RobotArm, arm_right: jacobi.RobotArm, start: jacobi.MultiRobotPoint, goal: jacobi.MultiRobotPoint) -> None
Construct a BimanualMotion with a name, left and right robot arms, start and goal point.
- Parameter
name
: The unique name of the motion.
- Parameter
arm_left
: The left robot arm for the motion.
- Parameter
arm_right
: The right robot arm for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.BimanualMotion, robot: jacobi::robots::DualArm, start: jacobi.MultiRobotPoint, goal: jacobi.MultiRobotPoint) -> None
Construct a BimanualMotion with a robot, start and goal point.
- Parameter
robot
: The dual-arm robot for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
__init__(self: jacobi.BimanualMotion, name: str, robot: jacobi::robots::DualArm, start: jacobi.MultiRobotPoint, goal: jacobi.MultiRobotPoint) -> None
Construct a BimanualMotion with a name, robot, start and goal point.
- Parameter
name
: The unique name of the motion.
- Parameter
robot
: The dual-arm robot for the motion.
- Parameter
start
: The start point of the motion.
- Parameter
goal
: The goal point of the motion.
- property goalΒΆ
Goal point of the motion for both arms.
- property is_coordinatedΒΆ
Flag to indicate if the motion is coordinated, in which case the follower arm moves with a constant offset to the leader arm.
- property leader_armΒΆ
The leader arm for the coordinated motion. Left arm is used by default if this variable is not set.
- property linear_approachΒΆ
Optional relative linear cartesian motion for approaching the goal pose, specified for one or both arms.
- property linear_retractionΒΆ
Optional relative linear cartesian motion for retracting from the start pose, specified for one or both arms.
- property nameΒΆ
The unique name of the bimanual motion.
- property robotΒΆ
The dual-arm robot for the bimanual motion (e.g. defines the kinematics and the joint limits).
- property startΒΆ
Start point of the motion for both arms.
- property waypointsΒΆ
Intermediate waypoints for both arms that the motion passes through exactly. The list of waypoints is limited to less than four.