WaypointsΒΆ

class jacobi.WaypointΒΆ

Bases: Element

A joint-space waypoint with possible position, velocity, and/or acceleration values.

The Waypoint class represents a point in the joint space of a robot with associated position, velocity, and acceleration values.

__init__(*args, **kwargs)ΒΆ

Overloaded function.

  1. __init__(self: jacobi.Waypoint, position: list[float]) -> None

Construct a waypoint by position data.

Parameter data:

A list of position values to initialize the waypoint.

  1. __init__(self: jacobi.Waypoint, position: list[float], velocity: list[float]) -> None

Construct a waypoint with given position and zero velocity and acceleration.

Parameter position:

The joint position to initialize the waypoint.

  1. __init__(self: jacobi.Waypoint, position: list[float], velocity: list[float], acceleration: list[float]) -> None

Construct a waypoint with given position and velocity and zero acceleration.

Parameter position:

The joint position to initialize the waypoint.

Parameter velocity:

The joint velocity to initialize the waypoint.

is_within(self: Waypoint, other: Waypoint) boolΒΆ
property accelerationΒΆ

The joint acceleration at the waypoint.

property positionΒΆ

The joint position at the waypoint.

property velocityΒΆ

The joint velocity at the waypoint.

class jacobi.CartesianWaypointΒΆ

Bases: Element

A Cartesian-space waypoint with possible position, velocity, and/or acceleration values.

The CartesianWaypoint class represents a point in Cartesian space with associated position, velocity, and acceleration frames. It is used to define the robot state in Cartesian space at a specific instance, with optional reference joint positions for inverse kinematics.

__init__(*args, **kwargs)ΒΆ

Overloaded function.

  1. __init__(self: jacobi.CartesianWaypoint, position: jacobi.Frame, reference_config: Optional[list[float]] = None) -> None

Construct a Cartesian waypoint with given position and zero velocity and acceleration.

Parameter position:

The position frame to initialize the waypoint.

Parameter reference_config:

An optional joint configuration for inverse kinematics.

  1. __init__(self: jacobi.CartesianWaypoint, position: jacobi.Frame, velocity: jacobi.Frame, reference_config: Optional[list[float]] = None) -> None

Construct a Cartesian waypoint with given position and velocity and zero acceleration.

Parameter position:

The position frame to initialize the waypoint.

Parameter velocity:

The velocity frame to initialize the waypoint.

Parameter reference_config:

An optional joint configuration for inverse kinematics.

  1. __init__(self: jacobi.CartesianWaypoint, position: jacobi.Frame, velocity: jacobi.Frame, acceleration: jacobi.Frame, reference_config: Optional[list[float]] = None) -> None

Construct a Cartesian waypoint with given position, velocity, and acceleration.

Parameter position:

The position frame to initialize the waypoint.

Parameter velocity:

The velocity frame to initialize the waypoint.

Parameter acceleration:

The acceleration frame to initialize the waypoint.

Parameter reference_config:

An optional joint configuration for inverse kinematics.

property accelerationΒΆ

Frame of the acceleration.

property positionΒΆ

Frame of the position.

property reference_configΒΆ

An optional joint position that is used as a reference for inverse kinematics.

property velocityΒΆ

Frame of the velocity.

class jacobi.RegionΒΆ

Bases: Element

A joint-space region with possible position, velocity, and/or acceleration values.

The Region class defines a region in joint space with boundaries on position, velocity, and acceleration. It is used to specify an area within which a the robot end-effector operates. The class provides methods to construct the region with varying levels of detail and to check if a given waypoint falls within the region’s boundaries.

__init__(self: Region, min_position: list[float], max_position: list[float]) NoneΒΆ
is_within(self: Region, other: Waypoint) boolΒΆ

Check if a given waypoint is within the region.

Parameter other:

The waypoint to check.

Returns:

true If the waypoint is within the region’s boundaries.

Returns:

false If the waypoint is not within the region’s boundaries.

This method checks if the given waypoint’s position, velocity, and acceleration fall within the respective boundaries defined by the region.

property max_accelerationΒΆ

Maximum acceleration boundary of the region.

property max_positionΒΆ

Maximum position boundary of the region.

property max_velocityΒΆ

Maximum velocity boundary of the region.

property min_accelerationΒΆ

Minimum acceleration boundary of the region.

property min_positionΒΆ

Minimum position boundary of the region.

property min_velocityΒΆ

Minimum velocity boundary of the region.

class jacobi.CartesianRegionBoundΒΆ

Bases: pybind11_object

The min or max boundary of a Cartesian region.

The CartesianRegionBound struct represents the boundaries of a region in Cartesian space. It defines both positional (x, y, z) and orientational (gamma, alpha) limits. These boundaries are used to constrain the movement or state of an object within a specified region.

__init__(self: CartesianRegionBound, x: float, y: float, z: float, gamma: float = 0.0, alpha: float = 0.0) NoneΒΆ
property alphaΒΆ

The rotational component around the x-axis (roll).

property gammaΒΆ

The rotational component around the z-axis (yaw).

property xΒΆ

The x-coordinate of the boundary.

property yΒΆ

The y-coordinate of the boundary.

property zΒΆ

The z-coordinate of the boundary.

class jacobi.CartesianRegionΒΆ

Bases: Element

A Cartesian-space region with possible minimum and maximum position, velocity, and/or acceleration values.

The CartesianRegion class defines a region in Cartesian space with optional boundaries for position, velocity, and acceleration. It is used to describe constraints on a Cartesian region within which the robot end-effector operates. The region can also have an associated reference configuration.

__init__(*args, **kwargs)ΒΆ

Overloaded function.

  1. __init__(self: jacobi.CartesianRegion, min_position: jacobi.CartesianRegionBound, max_position: jacobi.CartesianRegionBound, reference_config: Optional[list[float]] = None) -> None

  2. __init__(self: jacobi.CartesianRegion, min_position: jacobi.CartesianRegionBound, max_position: jacobi.CartesianRegionBound, min_velocity: jacobi.CartesianRegionBound, max_velocity: jacobi.CartesianRegionBound, reference_config: Optional[list[float]] = None) -> None

  3. __init__(self: jacobi.CartesianRegion, min_position: jacobi.CartesianRegionBound, max_position: jacobi.CartesianRegionBound, min_velocity: jacobi.CartesianRegionBound, max_velocity: jacobi.CartesianRegionBound, min_acceleration: jacobi.CartesianRegionBound, max_acceleration: jacobi.CartesianRegionBound, reference_config: Optional[list[float]] = None) -> None

property max_accelerationΒΆ

Maximum acceleration boundary of the region.

property max_positionΒΆ

Maximum position boundary of the region.

property max_velocityΒΆ

Maximum velocity boundary of the region.

property min_accelerationΒΆ

Minimum acceleration boundary of the region.

property min_positionΒΆ

Minimum position boundary of the region.

property min_velocityΒΆ

Minimum velocity boundary of the region.

property reference_configΒΆ

Reference configuration for the region, if any.

class MultiRobotPointΒΆ

Type alias for Dict[Robot, Config | Waypoint | CartesianWaypoint]. A type for specifying an exact start or goal point per robot.

class PointΒΆ

Type alias for Config | Waypoint | CartesianWaypoint | MultiRobotPoint | Region | CartesianRegion. All types for specifying motion start or goals, either exact or by region.

class ExactPointΒΆ

Type alias for Config | Waypoint | CartesianWaypoint | MultiRobotPoint. All types for specifying exact start or goal points.