Motion PlanningΒΆ

class jacobi.TrajectoryΒΆ

Bases: pybind11_object

A robot’s trajectory as a list of positions, velocities and accelerations at specific times.

The Trajectory class represents a sequence of kinematic states of a robot over a specified duration. It maintains lists of positions, velocities, and accelerations at particular time stamps.

__init__(self: Trajectory, degrees_of_freedom: int) NoneΒΆ

Create an empty trajectory with the given degrees of freedom

Parameter dofs:

The degrees of freedom of the joint space.

append(self: Trajectory, other: Trajectory) NoneΒΆ

Append another trajectory to the current one.

Parameter other:

The trajectory to append.

as_table(self: Trajectory) strΒΆ

To pretty print the trajectory as a table of positions

at_time(self: Trajectory, time: float) tupleΒΆ
back(self: Trajectory) jacobi.StateΒΆ

Access the last state at t=duration of the trajectory

Returns:

The last state at t=duration of the trajectory.

filter_path(self: Trajectory, max_distance: list[float]) list[list[float]]ΒΆ

Filter a path of sparse waypoints from the trajectory

The path has a maximum distance per degree of freedom between the linear interpolation of the sparse waypoints and the original trajectory.

Parameter max_distance:

The maximum allowable distance between joint positions.

Returns:

std::vector<Config> A list of sparse waypoints filtered from the trajectory.

static from_json(json: str) TrajectoryΒΆ

Loads a trajectory from a json string.

static from_json_file(file: os.PathLike) TrajectoryΒΆ

Loads a trajectory from a *.json file.

Parameter file:

The path to the *.json file.

Returns:

Trajectory The loaded trajectory.

front(self: Trajectory) jacobi.StateΒΆ

Access the first state at t=0 of the trajectory

Returns:

The first state at t=0 of the trajectory.

get_step_closest_to(self: Trajectory, position: list[float]) intΒΆ

Get step at which the trajectory is closest (in terms of the L2 norm in joint space) to the reference position

Returns:

size_t The step index of the closest position.

reverse(self: Trajectory) TrajectoryΒΆ

Reverse the trajectory’s start and goal

Returns:

Trajectory A new trajectory with the start and end points reversed.

scale(self: Trajectory, speed: float, keep_delta_time: bool = True) TrajectoryΒΆ

Temporally scale the trajectory by a given speed factor.

Parameter speed:

Factor to scale the trajectory speed (greater than 1 speeds up, less than 1 slows down).

Parameter keep_delta_time:

If true (default), maintains the original time intervals between trajectory points.

Returns:

Trajectory A new scaled Trajectory object.

slice(self: Trajectory, start: int, steps: int) TrajectoryΒΆ

Slice a trajectory starting from step start for a length of steps.

Parameter start:

The starting index of the slice.

Parameter steps:

The number of steps to include in the slice.

Returns:

Trajectory A new trajectory containing the specified slice of the original.

to_json(self: Trajectory) strΒΆ

Serializes a trajectory to a json string.

to_json_file(self: Trajectory, file: os.PathLike) NoneΒΆ

Saves a trajectory to a *.json file.

Parameter file:

The path to the *.json file.

update_first_position(self: Trajectory, joint_position: list[float]) NoneΒΆ

Update the first position of the trajectory

Parameter joint_position:

The new position to set at the start of the trajectory.

property accelerationsΒΆ

The joint accelerations along the trajectory.

property durationΒΆ

The total duration in [s]

property idΒΆ

Field for identifying trajectories (for the user)

property max_accelerationΒΆ

Get the maximum acceleration along the trajectory for each degree of freedom individually

Returns:

Config The maximum acceleration value for each degree of freedom across the trajectory.

property max_positionΒΆ

Get the maximum position along the trajectory for each degree of freedom individually

Returns:

Config The maximum position value for each degree of freedom across the trajectory.

property max_velocityΒΆ

Get the maximum velocity along the trajectory for each degree of freedom individually

Returns:

Config The maximum velocity value for each degree of freedom across the trajectory.

property min_accelerationΒΆ

Get the minimum acceleration along the trajectory for each degree of freedom individually

Returns:

Config The minimum acceleration value for each degree of freedom across the trajectory.

property min_positionΒΆ

Get the minimum position along the trajectory for each degree of freedom individually

Returns:

Config The minimum position value for each degree of freedom across the trajectory.

property min_velocityΒΆ

Get the minimum velocity along the trajectory for each degree of freedom individually

Returns:

Config The minimum velocity value for each degree of freedom across the trajectory.

property motionΒΆ

Name of the motion this trajectory was planned for

property positionsΒΆ

The joint positions along the trajectory.

property timesΒΆ

The exact time stamps for the position, velocity, and acceleration values. The times will usually be sampled at the delta_time distance of the Planner class, but might deviate at the final step.

property velocitiesΒΆ

The joint velocities along the trajectory.

class jacobi.DynamicRobotTrajectoryΒΆ

Bases: pybind11_object

A trajectory executed by a robot, in particular used for dynamic collision checking.

__init__(self: DynamicRobotTrajectory, trajectory: Trajectory, robot: Robot, time_offset: float = 0.0) NoneΒΆ
property robotΒΆ

The robot that executes the trajectory

property time_offsetΒΆ

A time offset when the robot starts executing the trajectory relative to the planning time

property trajectoryΒΆ

The execute trajectory

class jacobi.PlannerΒΆ

Bases: pybind11_object

__init__(*args, **kwargs)ΒΆ

Overloaded function.

  1. __init__(self: jacobi.Planner, environment: jacobi.Environment, delta_time: float) -> None

Create a planner with an environment and a specific delta time parameter.

Parameter environment:

The environment to plan the robot motions in.

Parameter delta_time:

The time step for sampling the trajectories in [s].

  1. __init__(self: jacobi.Planner, robot: jacobi.Robot, delta_time: float) -> None

Create a planner with the robot inside an empty environment and a specific delta time parameter.

Parameter robot:

The robot to plan the motions for.

Parameter delta_time:

The time step for sampling the trajectories in [s].

  1. __init__(self: jacobi.Planner, environment: jacobi.Environment) -> None

Create a planner with an environment.

Parameter environment:

The environment to plan the robot motions in.

  1. __init__(self: jacobi.Planner, robot: jacobi.Robot) -> None

Create a planner with the robot inside an empty environment.

Parameter robot:

The robot to plan the motions for.

add_motion(self: Planner, motion: BimanualMotion | LinearMotion | LowLevelMotion | Motion | PathFollowingMotion) NoneΒΆ

Add (or update when name already exists) a motion to the planner

Parameter motion:

The motion to add, can be of any type.

get_motion(self: Planner, name: str) BimanualMotion | LinearMotion | LowLevelMotion | Motion | PathFollowingMotionΒΆ

Get a motion by its name

Parameter name:

The name of the motion to retrieve.

Returns:

The AnyMotion object associated with the given name.

static load_from_json_file(file: os.PathLike, base_path: os.PathLike) PlannerΒΆ
static load_from_project_file(file: os.PathLike) PlannerΒΆ

Loads a planner from a project file.

Parameter file:

The path to the project file.

Returns:

A shared pointer to the loaded Planner object.

static load_from_studio(name: str) PlannerΒΆ

Loads a planner from a Studio project. Make sure to have the access token set as an environment variable.

Parameter name:

The name of the Studio project.

Returns:

A shared pointer to the loaded Planner object.

load_motion_plan(self: Planner, file: os.PathLike) NoneΒΆ

Load a *.jacobi-plan motion plan for accelerating the planning calculation.

Parameter file:

The path to the *.jacobi-plan file to load.

plan(*args, **kwargs)ΒΆ

Overloaded function.

  1. plan(self: jacobi.Planner, 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]) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a time-optimized, collision-free, and jerk-limited motion from start to goal.

Parameter start:

The start point of the motion.

Parameter goal:

The goal point of the motion.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, name: str, start: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None, goal: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a time-optimized, collision-free, and jerk-limited motion given the motion name. In case the motion was specified by a start or goal region, the respective exact start or goal positions needs to be passed.

Parameter name:

The name of the motion to plan.

Parameter start:

The exact start position of the motion.

Parameter goal:

The exact goal position of the motion.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motion: jacobi.Motion, start: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None, goal: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a collision-free point-to-point motion.

Parameter motion:

The motion to plan.

Parameter start:

The exact start position of the motion.

Parameter goal:

The exact goal position of the motion.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motion: jacobi.LinearMotion) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a linear motion.

Parameter motion:

The linear motion to plan.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motion: jacobi.LowLevelMotion) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a low-level motion.

Parameter motion:

The low-level motion to plan.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motion: jacobi.PathFollowingMotion) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a path-following motion.

Parameter motion:

The path-following motion to plan.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motion: jacobi.BimanualMotion) -> Expected[jacobi.Trajectory, jacobi.PlanningError]

Plans a bimanual motion.

Parameter motion:

The bimanual motion to plan.

Returns:

The computed trajectory or std::nullopt if the planning failed.

  1. plan(self: jacobi.Planner, motions: list[Union[jacobi.BimanualMotion, jacobi.LinearMotion, jacobi.LowLevelMotion, jacobi.Motion, jacobi.PathFollowingMotion]]) -> Expected[list[jacobi.Trajectory], jacobi.PlanningError]

Plans a feasible sequence of motions.

Parameter motions:

The sequence of motions to plan.

Returns:

The computed sequence of trajectories or std::nullopt if the planning failed.

plan_path(*args, **kwargs)ΒΆ

Overloaded function.

  1. plan_path(self: jacobi.Planner, motion: jacobi.Motion, start: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None, goal: Optional[Union[list[float], jacobi.Waypoint, jacobi.CartesianWaypoint, jacobi.MultiRobotPoint]] = None) -> Expected[jacobi.PathCommand, jacobi.PlanningError]

  2. plan_path(self: jacobi.Planner, motion: jacobi.BimanualMotion) -> Expected[jacobi.PathCommand, jacobi.PlanningError]

set_seed(self: Planner, seed: int | None) NoneΒΆ

Set the seed of the planner’s random number generator

Parameter seed:

The seed to set. If no seed is provided, the generator will be seeded with a random value.

transfer_trajectory(self: Planner, trajectory: Trajectory, robot_from: RobotArm, robot_to: RobotArm, offset: Frame = Frame()) Expected[Trajectory, jacobi.PlanningError]ΒΆ

Transfers a trajectory from one robot to another.

Calculate a trajectory for another robot that follows the TCP of the original robot given the trajectory. This method does not check for constraints of the new robot.

Parameter trajectory:

The trajectory to follow.

Parameter robot_from:

The original robot to transfer from.

Parameter robot_to:

The new robot to transfer to.

Parameter offset:

Optional offset between the from and to robot’s TCP.

Returns:

The transferred trajectory or std::nullopt if the planning failed.

property delta_timeΒΆ

The time step for sampling the trajectories in [s]. Usually, this should correspond to the control rate of the robot.

property dynamic_robot_trajectoriesΒΆ

Pairs of robot-trajectories that are used for dynamic collision checking (e.g. of moving robots)

property environmentΒΆ

The current environment to plan robot motions in

property initial_perturbation_scaleΒΆ

Initial perturbation for the trajectory optimization

property last_calculation_durationΒΆ

The calculation duration of the last full trajectory computation

property max_break_stepsΒΆ

Max number of steps without improvement before early stopping

property max_calculation_durationΒΆ

The maximum compute budget (that won’t be exceeded)

property max_optimization_stepsΒΆ

Maximum number of optimization steps

property meaningful_loss_improvementΒΆ

A meaningful relative improvement to avoid stopping

property min_calculation_durationΒΆ

The minimum compute budget (that the planner can use regardless)

property perturbation_change_stepsΒΆ

Steps without improvement after which the perturbation scale is adapted

property perturbation_scale_changeΒΆ

Change of the perturbation if no improvement could be found recently

property pre_eps_collisionΒΆ

Resolution of the collision checking in the pre-planning stage [rad]

property pre_eps_steeringΒΆ

Steering epsilon in the pre-planning stage [rad]

property pre_max_stepsΒΆ

Maximum number of steps in the pre-planning stage before a solution is not found

property pre_optimization_stepsΒΆ

Number of samples for optimization after finding a solution in the pre-plannning stage