PythonΒΆ
GeometryΒΆ
- class ConfigΒΆ
Type alias for
List[float]
as a joint configuration of a robot.
- class jacobi.FrameΒΆ
Bases:
pybind11_object
Represents a transformation or pose in 3D Cartesian space.
Encapsulates translation and rotation in a unified manner for 3D poses.
- __init__(self: Frame, *, x: float = 0.0, y: float = 0.0, z: float = 0.0, a: float = 0.0, b: float = 0.0, c: float = 0.0, qw: float = 1.0, qx: float = 0.0, qy: float = 0.0, qz: float = 0.0) None ΒΆ
- angular_distance(self: Frame, other: Frame) float ΒΆ
Calculate the angular distance between two Framesβ orientations.
- Parameter
other
: The other Frame to compare against.
- Returns:
double The angular distance.
- Parameter
- static from_euler(x: float, y: float, z: float, a: float, b: float, c: float) Frame ΒΆ
Create a Frame from Euler angles.
- Parameter
x
: The x translation.
- Parameter
y
: The y translation.
- Parameter
z
: The z translation.
- Parameter
a
: The rotation angle around the x-axis.
- Parameter
b
: The rotation angle around the y-axis.
- Parameter
c
: The rotation angle around the z-axis.
- Returns:
Frame The Frame with the specified translation and Euler angles.
- Parameter
- static from_matrix(data: Annotated[list[float], FixedSize(16)]) Frame ΒΆ
Create a Frame from a matrix.
- Parameter
data
: A 16-element array representing a 4x4 matrix.
- Returns:
Frame The Frame constructed from the matrix.
- Parameter
- static from_quaternion(x: float, y: float, z: float, qw: float, qx: float, qy: float, qz: float) Frame ΒΆ
Create a Frame from quaternion values.
- Parameter
x
: The x component of the quaternion.
- Parameter
y
: The y component of the quaternion.
- Parameter
z
: The z component of the quaternion.
- Parameter
qw
: The scalar component of the quaternion.
- Parameter
qx
: The x component of the quaternion.
- Parameter
qy
: The y component of the quaternion.
- Parameter
qz
: The z component of the quaternion.
- Returns:
Frame The Frame with the specified quaternion.
- Parameter
- static from_translation(x: float, y: float, z: float) Frame ΒΆ
Create a Frame from translation values.
- Parameter
x
: The x translation.
- Parameter
y
: The y translation.
- Parameter
z
: The z translation.
- Returns:
Frame The Frame with the specified translation.
- Parameter
- interpolate(self: Frame, t: float, other: Frame) Frame ΒΆ
Interpolate between this Frame and another Frame.
- Parameter
t
: The interpolation parameter (0.0 to 1.0).
- Parameter
other
: The other Frame to interpolate towards.
- Returns:
Frame The interpolated Frame.
- Parameter
- translational_distance(self: Frame, other: Frame) float ΒΆ
Calculate the Euclidean distance between two Framesβ positions.
- Parameter
other
: The other Frame to compare against.
- Returns:
double The Euclidean distance.
- Parameter
- property eulerΒΆ
Convert the Frame to Euler angles and translation.
- Returns:
std::array<double, 6> The Frame as Euler angles and translation.
- property matrixΒΆ
Convert the Frame to a 4x4 matrix.
- Returns:
std::array<double, 16> The Frame as a 4x4 matrix.
- class jacobi.TwistΒΆ
Bases:
pybind11_object
Represents a velocity in 3D Cartesian space.
The Twist struct represents a 6-dimensional vector used to describe velocity in 3D Cartesian space. It consists of linear velocities in the x, y, and z directions, and angular velocities around these axes.
ElementΒΆ
- class jacobi.ElementΒΆ
Bases:
pybind11_object
The base element of a scene
The Element struct represents the base element of a scene, such as a robot, camera, or obstacle. It contains a name, pose, and tags that can be used to identify and categorize the element.
- __init__(*args, **kwargs)ΒΆ
- get_parameter(self: Element, tag: str) str | None ΒΆ
Reads the value of a tag parameter param=value. Tags are case- insensitive.
- Parameter
tag
: The tag to read the parameter from.
- Returns:
std::optional<std::string> The value of the parameter if it exists, std::nullopt otherwise.
- Parameter
- has_tag(self: Element, tag: str) bool ΒΆ
Checks whether a tag is present on the element. Tags are case- insensitive.
- Parameter
tag
: The tag to check for.
- Returns:
bool True if the tag is present, false otherwise.
- Parameter
- property nameΒΆ
The unique name of the element, for display and identification.
- property originΒΆ
Pose of the element, relative to the parent. Is called βbaseβ for robots in Studio.
- property tagsΒΆ
Given tags of the element, might be with a parameter param=value.
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.
__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.
__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.
__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.
- 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.
__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.
__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.
__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.
- 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.
- Parameter
- 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.
__init__(self: jacobi.CartesianRegion, min_position: jacobi.CartesianRegionBound, max_position: jacobi.CartesianRegionBound, reference_config: Optional[list[float]] = None) -> None
__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
__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.
ObstaclesΒΆ
- class jacobi.BoxΒΆ
Bases:
pybind11_object
A box collision object.
The Box struct represents a simple 3D rectangular collision object. It is defined by its dimensions along the x, y, and z axes, which correspond to the width, depth, and height of the box, respectively.
- __init__(self: Box, x: float, y: float, z: float) None ΒΆ
Construct a box of size x, y, z along the respective axes.
- Parameter
x
: The width of the box along the x-axis.
- Parameter
y
: The depth of the box along the y-axis.
- Parameter
z
: The height of the box along the z-axis.
- Parameter
- property xΒΆ
Dimensions of the box [m]
- property yΒΆ
Dimensions of the box [m]
- property zΒΆ
Dimensions of the box [m]
- class jacobi.CapsuleΒΆ
Bases:
pybind11_object
A capsule collision object.
The Capsule struct represents a simple 3D collision object shaped like a capsule (a cylinder with hemispherical ends). It is defined by its radius and length along the z-axis. Capsules are commonly used in collision detection due to their computational efficiency.
- __init__(self: Capsule, radius: float, length: float) None ΒΆ
Construct a capsule with the given radius and length.
- Parameter
radius
: The radius of the capsule.
- Parameter
length
: The length of the capsule along the z-axis.
- Parameter
- property lengthΒΆ
Length of the capsule along the z-axis [m]
- property radiusΒΆ
Radius of the capsule [m]
- class jacobi.ConvexΒΆ
Bases:
pybind11_object
A convex mesh collision object.
The Convex struct represents a 3D convex mesh, often used for collision detection. It supports loading from files, direct vertex and triangle specification, and provides utility functions like bounding box computation.
- __init__(self: Convex, vertices: list[Annotated[list[float], FixedSize(3)]], triangles: list[Annotated[list[int], FixedSize(3)]]) None ΒΆ
- static load_from_file(path: os.PathLike, scale: float | None = None) list[Convex] ΒΆ
Load convex objects from a file.
- Parameter
path
: The path to the file (*.obj).
- Parameter
scale
: Optional scale to apply when loading the object.
- Returns:
A vector of Convex objects loaded from the file.
- Parameter
- static reference_studio_file(path: os.PathLike, scale: float | None = None) Convex ΒΆ
Create a reference to a Studio file.
- Parameter
path
: The path to the Studio file.
- Parameter
scale
: Optional scale to apply when referencing the file.
- Returns:
A Convex object that references the specified Studio file.
- Parameter
- property bounding_box_maximumΒΆ
Get the maximum bounding box corner.
- Returns:
A 3D vector representing the maximum corner of the bounding box.
- property bounding_box_minimumΒΆ
Get the minimum bounding box corner.
- Returns:
A 3D vector representing the minimum corner of the bounding box.
- property file_referenceΒΆ
Optional file reference from which the convex object was loaded.
- class jacobi.CylinderΒΆ
Bases:
pybind11_object
A cylinder collision object.
The Cylinder struct represents a 3D cylindrical collision object. It is defined by its radius and length along the z-axis.
- __init__(self: Cylinder, radius: float, length: float) None ΒΆ
Construct a cylinder with the given radius and length.
- Parameter
radius
: The radius of the cylinder.
- Parameter
length
: The length of the cylinder along the z-axis.
- Parameter
- property lengthΒΆ
Length of the cylinder along the z-axis [m].
- property radiusΒΆ
Radius of the cylinder [m].
- class jacobi.DepthMapΒΆ
Bases:
pybind11_object
A depth map collision object.
The DepthMap struct represents a 3D collision object based on a depth map, which is essentially a grid of depth values.
- __init__(self: DepthMap, depths: list[list[float]], x: float, y: float) None ΒΆ
Construct a depth map with the given data.
- Parameter
depths
: The matrix of depth values.
- Parameter
x
: The size of the depth map along the x-axis.
- Parameter
y
: The size of the depth map along the y-axis.
- Parameter
- property depthsΒΆ
Matrix containing the depth values at evenly spaced grid points.
- property max_depthΒΆ
Maximum depth to check for collisions [m].
This value sets the maximum depth that will be considered during collision checking. Any depth greater than this value will be ignored. The default value is 100 meters.
- property xΒΆ
Size along the x-axis [m].
- property yΒΆ
Size along the y-axis [m].
- class jacobi.SphereΒΆ
Bases:
pybind11_object
A sphere collision object.
The Sphere struct represents a 3D spherical collision object, defined by its radius, which determines its size in all directions.
- __init__(self: Sphere, radius: float) None ΒΆ
Construct a sphere with the given radius.
- Parameter
radius
: The radius of the sphere.
Initializes the sphere with the specified radius.
- Parameter
- property radiusΒΆ
Radius of the sphere [m]
- class jacobi.ObstacleΒΆ
Bases:
Element
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.Obstacle, collision: jacobi.Box, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: jacobi.Capsule, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: jacobi.Convex, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: list[jacobi.Convex], origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: jacobi.Cylinder, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: jacobi.DepthMap, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, collision: jacobi.Sphere, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.Box, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.Capsule, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.Convex, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: list[jacobi.Convex], origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.Cylinder, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.DepthMap, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
__init__(self: jacobi.Obstacle, name: str, collision: jacobi.Sphere, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> None
- with_name(self: Obstacle, name: str) Obstacle ΒΆ
Clone the current obstacle and update some parameters.
Creates a copy of the current obstacle and updates its name. This function is useful for creating modified versions of an obstacle without altering the original object.
- Parameter
name
: The new name for the cloned obstacle.
- Returns:
Obstacle A new Obstacle instance with the updated origin.
- Parameter
- with_origin(self: Obstacle, origin: Frame) Obstacle ΒΆ
Clone the current obstacle and set the new origin.
Creates a copy of the current obstacle and updates its origin to the provided frame. This function is useful for creating modified versions of an obstacle without altering the original object.
- Parameter
origin
: The new pose (origin) for the cloned obstacle.
- Returns:
Obstacle A new Obstacle instance with the updated origin.
- Parameter
- property collisionΒΆ
The object for collision checking (and/or visualization).
This variant holds the geometric representation of the obstacle. It can be any of the supported shapes, including Box, Capsule, Convex, ConvexVector, Cylinder, DepthMap, or Sphere.
- property colorΒΆ
The hex-string representation of the obstacleβs color, without the leading #.
This string defines the color of the obstacle for visualization purposes, formatted as a hex code (e.g., βFF5733β for orange).
- property for_collisionΒΆ
Whether this obstacle is used for collision checking.
If true, the obstacle will be considered in collision detection calculations. By default, this is set to true.
- property for_visualΒΆ
Whether this obstacle is used for visualization.
If true, the obstacle will be rendered in the environmentβs visualization in Studio. By default, this is set to true.
- property safety_marginΒΆ
An additional obstacle-specific safety margin for collision checking (on top of the environmentβs global safety margin).
This margin adds an extra buffer around the obstacle during collision detection. It is specific to this obstacle and is added on top of any global safety margins.
- class MatrixΒΆ
Type alias for
List[List[float]]
.
EnvironmentΒΆ
- class jacobi.EnvironmentΒΆ
Bases:
pybind11_object
The environment a robot (or multiple robots) lives in
The Environment class manages static obstacles, collision checking, waypoints, cameras, and robots within a defined environment. The class provides methods to add, remove, and manage obstacles and waypoints, as well as to retrieve information about these elements. It also includes functionality for collision checking and updating the state of obstacles and robots.
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.Environment, robot: jacobi.Robot, safety_margin: float = 0.0) -> None
Create an environment with a controllable robot
- Parameter
robot
: The robot to add to the environment.
- Parameter
safety_margin
: The global safety margin for collision checking [m].
__init__(self: jacobi.Environment, robots: set[jacobi.Robot], safety_margin: float = 0.0) -> None
Create an environment with multiple robots
- Parameter
robots
: The robots to add to the environment.
- Parameter
safety_margin
: The global safety margin for collision checking [m].
- add_obstacle(*args, **kwargs)ΒΆ
Overloaded function.
add_obstacle(self: jacobi.Environment, obstacle: jacobi.Obstacle) -> jacobi.Obstacle
Add an obstacle to the environment (and returns the pointer to it)
- Parameter
obstacle
: The obstacle to add to the environment.
- Returns:
The original shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.Box, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a box-shaped obstacle to the environment
- Parameter
object
: The box-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.Capsule, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a capsule-shaped obstacle to the environment
- Parameter
object
: The capsule-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.Convex, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a convex-shaped obstacle to the environment
- Parameter
object
: The convex-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: list[jacobi.Convex], origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a vector of convex-shaped obstacles to the environment
- Parameter
object
: The vector of convex-shaped obstacles to add.
- Parameter
origin
: The initial pose of the obstacles in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacles in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacles (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.Cylinder, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a cylinder-shaped obstacle to the environment
- Parameter
object
: The cylinder-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.DepthMap, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a depth map-shaped obstacle to the environment
- Parameter
object
: The depth map-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, object: jacobi.Sphere, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a sphere-shaped obstacle to the environment
- Parameter
object
: The sphere-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.Box, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add an obstacle with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The obstacle to add (of a specific type, e.g., Box, Capsule, etc.).
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.Capsule, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Overload for adding an obstacle with a name and various shapes
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The obstacle to add (of a specific type, e.g., Capsule, Convex, etc.).
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.Convex, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a convex-shaped obstacle with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The convex-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: list[jacobi.Convex], origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a vector of convex-shaped obstacles with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The vector of convex-shaped obstacles to add.
- Parameter
origin
: The initial pose of the obstacles in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacles in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacles (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.Cylinder, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a cylinder-shaped obstacle with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The cylinder-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.DepthMap, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a depth map-shaped obstacle with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The depth map-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
add_obstacle(self: jacobi.Environment, name: str, object: jacobi.Sphere, origin: jacobi.Frame = Frame(), color: str = β000000β, safety_margin: float = 0.0) -> jacobi.Obstacle
Add a sphere-shaped obstacle with a name to the environment
- Parameter
name
: The name to assign to the obstacle.
- Parameter
object
: The sphere-shaped obstacle to add.
- Parameter
origin
: The initial pose of the obstacle in the environment (default is Frame::Identity()).
- Parameter
color
: The color of the obstacle in hexadecimal format (default is β000000β).
- Parameter
safety_margin
: The safety margin around the obstacle (default is 0.0).
- Returns:
A shared pointer to the added obstacle.
- check_collision(*args, **kwargs)ΒΆ
Overloaded function.
check_collision(self: jacobi.Environment, robot: jacobi.Robot, joint_position: list[float]) -> bool
check_collision(self: jacobi.Environment, joint_position: list[float]) -> bool
check_collision(self: jacobi.Environment, robot: jacobi.Robot, waypoint: jacobi.CartesianWaypoint) -> bool
check_collision(self: jacobi.Environment, robot: jacobi.Robot, tcp: jacobi.Frame, reference_config: Optional[list[float]] = None) -> bool
check_collision(self: jacobi.Environment, tcp: jacobi.Frame, reference_config: Optional[list[float]] = None) -> bool
check_collision(self: jacobi.Environment, waypoint: jacobi.CartesianWaypoint) -> bool
- get_camera(self: Environment, name: str = '') Camera ΒΆ
Get a camera from the environment
- Parameter
name
: Optional parameter to specify the name of the camera. If not provided, an empty string defaults to retrieving a camera without a specific name.
- Returns:
A shared pointer to the camera associated with the given name, or a default camera if the name is empty.
- Parameter
- get_collision_free_joint_position_nearby(self: Environment, joint_position: list[float], robot: Robot = None) list[float] | None ΒΆ
- get_obstacle(self: Environment, name: str) Obstacle ΒΆ
Get the obstacle with the given name from the environment. Throws an error if no obstacle with the name exists.
- Parameter
name
: The name of the obstacle to retrieve.
- Returns:
A shared pointer to the obstacle associated with the given name.
- Parameter
- get_obstacles(self: Environment) list[Obstacle] ΒΆ
Get all obstacles within the environment
This function retrieves a list of all obstacles present in the environment.
- Returns:
A vector of shared pointers to the obstacles within the environment.
- get_obstacles_by_tag(self: Environment, tag: str) list[Obstacle] ΒΆ
Get all obstacles within the environment that carry the given tag.
- Parameter
tag
: The tag associated with the obstacles to retrieve.
- Returns:
A vector of shared pointers to the obstacles that have the specified tag.
- Parameter
- get_robot(self: Environment, name: str = '') Robot ΒΆ
Get the robot with the given name from the environment.
In case there is only a single robot in the environment, the default empty name argument will return this robot. Otherwise throws an error if no robot with the name exists.
- Parameter
name
: The name of the robot to retrieve.
- Returns:
The shared pointer to a robot object associated with the given name.
- Parameter
- get_robots(self: Environment) list[Robot] ΒΆ
Get all robots within the environment
- Returns:
A vector of shared pointers to the robots within the environment.
- get_waypoint(self: Environment, name: str) list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion ΒΆ
Get the waypoint with the given name from the environment. Throws an error if no waypoint with the name exists.
- Parameter
name
: The name of the waypoint to retrieve.
- Returns:
The waypoint associated with the given name.
- Parameter
- get_waypoint_by_tag(self: Environment, tag: str) list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion | None ΒΆ
Get a waypoint within the environment given a tag. If multiple waypoints have the same tag, the first one to be found is returned.
- Parameter
tag
: The tag associated with the waypoint to retrieve.
- Returns:
An optional containing the waypoint associated with the given tag, or std::nullopt if no waypoint with the tag is found.
- Parameter
- get_waypoints(self: Environment) list[list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion] ΒΆ
Get all waypoints within the environment
This function retrieves a list of all waypoints present in the environment.
- Returns:
A vector of waypoints within the environment.
- get_waypoints_by_tag(self: Environment, tag: str) list[list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion] ΒΆ
Get all waypoints within the environment given a tag.
- Parameter
tag
: The tag associated with the waypoints to retrieve.
- Returns:
A vector of waypoints that have the specified tag.
- Parameter
- remove_obstacle(*args, **kwargs)ΒΆ
Overloaded function.
remove_obstacle(self: jacobi.Environment, obstacle: jacobi.Obstacle) -> None
Removes the given obstacles from the environment and from all collision checking.
- Parameter
obstacle
: The obstacle to remove from the environment.
remove_obstacle(self: jacobi.Environment, name: str) -> None
Removes all obstacles with the given name from the environment and from all collision checking.
- Parameter
name
: The name of the obstacle to remove from the environment.
- update_depth_map(self: Environment, obstacle: Obstacle) None ΒΆ
Updates the depths matrix of a given depth map obstacle for the internal collision checking.
- Parameter
obstacle
: The obstacle to update the depths map for.
- Parameter
- update_fixed_obstacles(self: Environment) None ΒΆ
Updates all fixed obstacles for the internal collision checking. This should be called after changing e.g. the position or size of an obstacle.
- update_joint_position(self: Environment, robot: Robot, joint_position: list[float]) None ΒΆ
Updates the joint position of the given robot for the internal collision checking.
- Parameter
robot
: The robot to update the joint position for.
- Parameter
joint_position
: The new joint position to set for the robot.
- Parameter
- update_robot(self: Environment, robot: Robot = None) None ΒΆ
Updates the given robot (or the default one if none was given) for the internal collision checking.
- Parameter
robot
: The robot to update the collision model for.
- Parameter
- property safety_marginΒΆ
Environmentβs global safety margin for collision checking [m]
- Returns:
The global safety margin for collision checking [m].
RobotsΒΆ
- class jacobi.RobotΒΆ
Bases:
Element
- __init__(*args, **kwargs)ΒΆ
- property modelΒΆ
The model name of the robot
- class jacobi.RobotArmΒΆ
Bases:
Robot
- __init__(*args, **kwargs)ΒΆ
- calculate_tcp(self: RobotArm, joint_position: list[float]) Frame ΒΆ
Calculates the forward_kinematics and returns the frame of the robotβs TCP.
- Parameter
joint_position
: The joint position of the robot.
- Returns:
The frame of the robotβs TCP.
- Parameter
- calculate_tcp_speed(self: RobotArm, joint_position: list[float], joint_velocity: list[float]) float ΒΆ
Calculates the forward_kinematics and returns the norm of the Cartesian velocity of the robotβs TCP.
- Parameter
joint_position
: The joint position of the robot.
- Parameter
joint_velocity
: The joint velocity of the robot.
- Returns:
The Cartesian speed of the TCP.
- Parameter
- inverse_kinematics(*args, **kwargs)ΒΆ
Overloaded function.
inverse_kinematics(self: jacobi.RobotArm, waypoint: jacobi.CartesianWaypoint) -> Optional[list[float]]
Computes the inverse kinematics for a Cartesian waypoint.
- Parameter
waypoint
: The Cartesian waypoint to compute the inverse kinematics for.
- Returns:
An optional Config object representing the joint positions of the robot.
inverse_kinematics(self: jacobi.RobotArm, tcp: jacobi.Frame, reference_config: Optional[list[float]] = None) -> Optional[list[float]]
Computes the inverse kinematics for a Cartesian position and a reference configuration.
Finds a joint position so that the robotβs TCP is at the given frame, which is defined in the world coordinate system. In general, the solution will try to stay close to the reference_config parameter. We use a numerical optimization for robots with more than 6 degrees of freedom. Then, the reference configuration is used as a starting point for the optimization. This method does not take the environmentβs collision model into account.
- Parameter
tcp
: The Cartesian position to compute the inverse kinematics for.
- Parameter
reference_config
: The reference configuration to use for the inverse kinematics.
- Returns:
An optional Config object representing the joint positions of the robot.
- set_speed(self: RobotArm, speed: float) None ΒΆ
Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.
- Parameter
speed
: A double representing the speed to be set for the robot.
- Parameter
- property default_positionΒΆ
The default robot position - used for initializing the current robot position.
- property degrees_of_freedomΒΆ
The degrees of freedom (or number of axis) of the robot.
- property end_effectorΒΆ
Get the (optional) end effector attached to the robotβs flange.
- Returns:
An (optional) end effector attached to the robotβs flange.
- property end_effector_obstacleΒΆ
internal An (optional) obstacle attached to the robotβs flange.
- property flange_to_tcpΒΆ
internal The transformation from the robotβs flange to the robotβs TCP, e.g., for using inverse kinematics or an item obstacle.
- property itemΒΆ
Get the (optional) obstacle attached to the robotβs TCP.
- Returns:
An (optional) obstacle attached to the robotβs TCP.
- property item_obstacleΒΆ
internal An (optional) obstacle attached to the robotβs TCP.
- property link_obstaclesΒΆ
The obstacles for each robot link.
- property max_accelerationΒΆ
Maximum absolute acceleration for each joint. [rad/s^2]
- property max_jerkΒΆ
Maximum absolute jerk for each joint. [rad/s^3]
- property max_positionΒΆ
Maximum position for each joint. [rad]
- property max_velocityΒΆ
Maximum absolute velocity for each joint. [rad/s]
- property min_positionΒΆ
Minimum position for each joint. [rad]
- property tcpΒΆ
Retrieves the frame of the robotβs TCP.
- Returns:
A Frame representing the frame of the robotβs TCP.
- property tcp_accelerationΒΆ
Retrieves the Cartesian acceleration of the robotβs TCP.
- Returns:
A Twist representing the Cartesian acceleration of the robotβs TCP.
- property tcp_positionΒΆ
Retrieves the frame of the robotβs TCP.
- Returns:
A Frame representing the frame of the robotβs TCP.
- property tcp_velocityΒΆ
Retrieves the Cartesian velocity of the robotβs TCP.
- Returns:
A Twist representing the Cartesian velocity of the robotβs TCP.
- class jacobi.robots.DualArmΒΆ
Bases:
Robot
- property leftΒΆ
The left arm of the robot
- property rightΒΆ
The right arm of the robot
- class jacobi.robots.ABBIRB1200590ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB1200590) None ΒΆ
- class jacobi.robots.ABBIRB1300714ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB1300714) None ΒΆ
- class jacobi.robots.ABBIRB1600612ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB1600612) None ΒΆ
- class jacobi.robots.ABBIRB260012185ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB260012185) None ΒΆ
- class jacobi.robots.ABBIRB460060205ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB460060205) None ΒΆ
- class jacobi.robots.ABBIRB6700150320ΒΆ
Bases:
RobotArm
- __init__(self: ABBIRB6700150320) None ΒΆ
- class jacobi.robots.ABBYuMiIRB14000ΒΆ
Bases:
DualArm
- __init__(self: ABBYuMiIRB14000) None ΒΆ
- class jacobi.robots.FanucCRX30iAΒΆ
Bases:
RobotArm
- __init__(self: FanucCRX30iA) None ΒΆ
- class jacobi.robots.FanucLR10iA10ΒΆ
Bases:
RobotArm
- __init__(self: FanucLR10iA10) None ΒΆ
- class jacobi.robots.FanucLRMate200iD7LΒΆ
Bases:
RobotArm
- __init__(self: FanucLRMate200iD7L) None ΒΆ
- class jacobi.robots.FanucM20iB25ΒΆ
Bases:
RobotArm
- __init__(self: FanucM20iB25) None ΒΆ
- class jacobi.robots.FanucM710iC45MΒΆ
Bases:
RobotArm
- __init__(self: FanucM710iC45M) None ΒΆ
- class jacobi.robots.FrankaPandaΒΆ
Bases:
RobotArm
- __init__(self: FrankaPanda) None ΒΆ
- class jacobi.robots.KinovaGen37DoFΒΆ
Bases:
RobotArm
- __init__(self: KinovaGen37DoF) None ΒΆ
- class jacobi.robots.MecademicMeca500ΒΆ
Bases:
RobotArm
- __init__(self: MecademicMeca500) None ΒΆ
- class jacobi.robots.UfactoryXArm7ΒΆ
Bases:
RobotArm
- __init__(self: UfactoryXArm7) None ΒΆ
- class jacobi.robots.UniversalUR5eΒΆ
Bases:
RobotArm
- __init__(self: UniversalUR5e) None ΒΆ
- class jacobi.robots.UniversalUR10ΒΆ
Bases:
RobotArm
- __init__(self: UniversalUR10) None ΒΆ
- class jacobi.robots.UniversalUR10eΒΆ
Bases:
RobotArm
- __init__(self: UniversalUR10e) None ΒΆ
- class jacobi.robots.UniversalUR20ΒΆ
Bases:
RobotArm
- __init__(self: UniversalUR20) None ΒΆ
- class jacobi.robots.YaskawaGP12ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaGP12) None ΒΆ
- class jacobi.robots.YaskawaGP180ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaGP180) None ΒΆ
- class jacobi.robots.YaskawaGP180120ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaGP180120) None ΒΆ
- class jacobi.robots.YaskawaGP50ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaGP50) None ΒΆ
- class jacobi.robots.YaskawaHC10ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaHC10) None ΒΆ
- class jacobi.robots.YaskawaHC20ΒΆ
Bases:
RobotArm
- __init__(self: YaskawaHC20) None ΒΆ
Warning
Custom robots are in a beta preview with rudimentary support right now. If possible, use robots from our supported robot library, as they will be significantly faster to compute and easier to use.
- class jacobi.robots.CustomRobotΒΆ
Bases:
RobotArm
A custom robot arm that can be loaded from a URDF file.
The CustomRobot class extends the RobotArm class and provides the functionality to load a robotβs configuration from a URDF (Unified Robot Description Format) file. It also includes methods for handling inverse kinematics and filtering relevant configurations.
- class JointTypeΒΆ
Bases:
pybind11_object
Types of joints that can be present in the robot.
Members:
Revolute : A revolute joint that allows rotation.
Continuous : A continuous joint that allows unlimited rotation.
Prismatic : A prismatic joint that allows linear motion.
Fixed : A fixed joint that does not allow any motion.
- property nameΒΆ
- __init__(*args, **kwargs)ΒΆ
Overloaded function.
__init__(self: jacobi.robots.CustomRobot, degrees_of_freedom: int) -> None
__init__(self: jacobi.robots.CustomRobot, degrees_of_freedom: int, number_joints: int) -> None
- static load_from_urdf_file(file: os.PathLike, base_link: str = 'base_link', end_link: str = 'flange') CustomRobot ΒΆ
Load the robot from a URDF file
Loads a custom robot from a *.urdf file, and sets the robot arm to the kinematic chain between the given base_link and the end_link.
- Parameter
file
: The path to the URDF file.
- Parameter
base_link
: The name of the base link in the URDF.
- Parameter
end_link
: The name of the end link in the URDF.
- Returns:
A shared pointer to the loaded robot.
- Parameter
- property childΒΆ
Possible child robot.
- property config_joint_namesΒΆ
Names of the joints corresponding to a specific joint configuration.
- property joint_axesΒΆ
Axes of the joints in the robot.
- property joint_namesΒΆ
Names of the joints in the robot.
- property joint_typesΒΆ
The type of the joints: Currently revolute, continuous, prismatic, and fixed joints are supported.
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.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.
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.
- Parameter
- append(self: Trajectory, other: Trajectory) None ΒΆ
Append another trajectory to the current one.
- Parameter
other
: The trajectory to append.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
__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].
__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].
__init__(self: jacobi.Planner, environment: jacobi.Environment) -> None
Create a planner with an environment.
- Parameter
environment
: The environment to plan the robot motions in.
__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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- 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.
- Parameter
- plan(*args, **kwargs)ΒΆ
Overloaded function.
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.
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.
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.
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.
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.
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.
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.
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(self: Planner, motion: Motion, start: list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | None = None, goal: list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | None = None) Expected[jacobi.PathCommand, jacobi.PlanningError] ΒΆ
internal Plans a collision-free path
- 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.
- Parameter
- 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.
- Parameter
- 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
Studio LiveΒΆ
- class jacobi.StudioΒΆ
Bases:
pybind11_object
Helper class to connect and visualize trajectories and events in Jacobi Studio.
The Studio class provides functionality to connect to Jacobi Studio via a WebSocket, and to visualize trajectories and events. It manages the connection, handles incoming and outgoing messages, and allows the user to create and execute actions within Jacobi Studio.
- class ActionΒΆ
Bases:
pybind11_object
An action that can be performed in Jacobi Studio.
The Action class represents an action in Jacobi Studio, such as setting a robotβs joint position, adding an obstacle, or manipulating the environment. An action can contain multiple commands, allowing for complex interactions in Studio.
- __init__(*args, **kwargs)ΒΆ
- class EventsΒΆ
Bases:
pybind11_object
A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).
The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.
- __init__(self: Events) None ΒΆ
A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).
The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.
- static add_camera(camera: Camera) Action ΒΆ
Returns an action that adds a camera.
- Parameter
camera
: The camera to be added.
- Returns:
The action to add the camera.
- Parameter
- static add_obstacle(obstacle: Obstacle) Action ΒΆ
Returns an action that adds the given obstacle to the environment.
- Parameter
obstacle
: The obstacle to be added.
- Returns:
The action to add the obstacle.
- Parameter
- static add_robot(robot: Robot) Action ΒΆ
Returns an action that adds the given robot to the environment.
- Parameter
robot
: The robot to be added.
- Returns:
The action to add the robot.
- Parameter
- static add_robot_path(points: list[list[float]], robot: Robot = None, name: str = '', color: str = '', stroke: float = -1.0, arrow_size: float = 1.0) Action ΒΆ
Returns an action that adds a visualization of a path for the given robot.
- Parameter
points
: The points defining the path.
- Parameter
robot
: Optional robot associated with the path.
- Parameter
name
: Optional name for the path.
- Parameter
color
: Optional color for the path visualization.
- Parameter
stroke
: Optional stroke width for the path visualization.
- Parameter
arrow_size
: Optional size of arrow for end of path
- Returns:
The action to add the robot path visualization.
- Parameter
- static add_waypoint(point: list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion) Action ΒΆ
Returns an action that adds the given Cartesian waypoint to the environment.
- Parameter
point
: The Cartesian waypoint to be added.
- Returns:
The action to add the Cartesian waypoint.
- Parameter
- static remove_camera(camera: Camera) Action ΒΆ
Returns an action that removes a camera.
- Parameter
camera
: The camera to be removed.
- Returns:
The action to remove the camera.
- Parameter
- static remove_obstacle(obstacle: Obstacle) Action ΒΆ
Returns an action that removes the given obstacle (by name) from the environment.
- Parameter
obstacle
: The obstacle to be removed.
- Returns:
The action to remove the obstacle.
- Parameter
- static remove_robot_path(robot: Robot, name: str) Action ΒΆ
Returns an action that removes a visualization of a named path for the given robot.
- Parameter
robot
: The robot associated with the path.
- Parameter
name
: The name of the path to be removed.
- Returns:
The action to remove the robot path visualization.
- Parameter
- static set_camera_depth_map(depths: list[list[float]], x: float, y: float, camera: Camera = None) Action ΒΆ
Returns an action that sets the depth map visualization of a camera.
- Parameter
depths
: The depth map data.
- Parameter
x
: Size of the depth map along the x-axis.
- Parameter
y
: Size of the depth map along the y-axis.
- Parameter
camera
: Optional camera associated with the depth map.
- Returns:
The action to set the camera depth map.
- Parameter
- static set_camera_image_encoded(image: str, camera: Camera) Action ΒΆ
Returns an action that sets an image for a camera encoded as a string.
- Parameter
image
: The encoded image to be set.
- Parameter
camera
: Optional camera associated with the image.
- Returns:
The action to set the camera image.
- Parameter
- static set_end_effector(obstacle: Obstacle | None, robot: Robot = None) Action ΒΆ
Returns an action that sets the end-effector obstacle of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Returns:
The action to set the item obstacle.
- Parameter
- static set_io_signal(name: str, value: int | float, robot: Robot = None) Action ΒΆ
Returns an action that sets an I/O signal of the given robot, or the last active robot instead.
- Parameter
name
: The name of the I/O signal.
- Parameter
value
: The value to be set for the I/O signal.
- Parameter
robot
: Optional robot associated with the I/O signal.
- Returns:
The action to set the I/O signal.
- Parameter
- static set_item(obstacle: Obstacle | None, robot: Robot = None) Action ΒΆ
Returns an action that sets the item obstacle of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Returns:
The action to set the item obstacle.
- Parameter
- static set_joint_position(joint_position: list[float], robot: Robot = None) Action ΒΆ
Returns an action that sets the joint position of the given robot, or the last active robot instead.
- Parameter
joint_position
: The desired joint position.
- Parameter
robot
: Optional robot to set the joint position for.
- Returns:
The action to set the joint position.
- Parameter
- static set_material(material: str, robot: Robot = None) Action ΒΆ
Returns an action that sets the material of the given robot, or the last active robot instead.
- Parameter
material
: The material to be set.
- Parameter
robot
: Optional robot associated with the material.
- Returns:
The action to set the material.
- Parameter
- __init__(self: Studio, auto_sync: bool = False, auto_connect: bool = True, timeout: float = 3.0) None ΒΆ
Interface Jacobi Studio via code. Connects to Jacobi Studio automatically - please make sure to enable the Studio Live feature in the Jacobi Studio settings.
- Parameter
auto_sync
: Whether to sync changes of the environment to Studio Live automatically. Only a subset of commands are supported right now, including: Environment::add_obstacle, Environment::remove_obstacle, Environment::update_joint_position, RobotArm::set_end_effector, RobotArm::set_item
- Parameter
auto_connect
: Whether to connect to Studio Live automatically.
- Parameter
timeout
: The timeout for connecting to Studio Live.
- Parameter
- add_camera(self: Studio, camera: Camera) bool ΒΆ
Adds a camera in Jacobi Studio.
- Parameter
camera
: The camera to be added.
- Parameter
- add_obstacle(self: Studio, obstacle: Obstacle) bool ΒΆ
Adds the given obstacle to the environment.
- Parameter
obstacle
: The obstacle to be added.
- Parameter
- add_robot(self: Studio, robot: Robot) bool ΒΆ
Adds the given robot to the environment.
- Parameter
robot
: The robot to be added.
- Parameter
- add_robot_path(self: Studio, points: list[list[float]], robot: Robot = None, name: str = '', color: str = '', stroke: float = -1.0, arrow_size: float = 1.0) bool ΒΆ
Adds a visualization of a path for the given robot.
- Parameter
points
: The points defining the path.
- Parameter
robot
: Optional robot associated with the path.
- Parameter
name
: Optional name for the path.
- Parameter
color
: Optional color for the path visualization.
- Parameter
stroke
: Optional stroke width for the path visualization.
- Parameter
arrow_size
: Optional size of arrow for end of path
- Parameter
- add_waypoint(self: Studio, point: list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion) bool ΒΆ
Adds the given Cartesian waypoint to the environment.
- Parameter
point
: The Cartesian waypoint to be added.
- Parameter
- get_camera_image_encoded(self: Studio, stream: jacobi.CameraStream, camera: Camera = None) str ΒΆ
Get an image from a camera encoded as a string.
- Parameter
stream
: The type of camera stream to get.
- Parameter
camera
: Optional camera to get the image from.
- Returns:
The encoded image from the camera.
- Parameter
- get_joint_position(self: Studio, robot: Robot = None) list[float] ΒΆ
Get the joint position of a robot.
- Parameter
robot
: Optional robot to get the joint position for.
- Returns:
The joint position of the robot.
- Parameter
- reconnect(self: Studio, timeout: float = 3.0) bool ΒΆ
Reconnect to Studio Live
- Parameter
timeout
: The timeout for reconnecting to Studio Live.
- Returns:
Whether the reconnection was successful.
- Parameter
- remove_camera(self: Studio, camera: Camera) bool ΒΆ
Removes a camera in Jacobi Studio.
- Parameter
camera
: The camera to be removed.
- Parameter
- remove_obstacle(self: Studio, obstacle: Obstacle) bool ΒΆ
Removes the given obstacle (by name) from the environment.
- Parameter
obstacle
: The obstacle to be removed.
- Parameter
- remove_robot_path(self: Studio, robot: Robot, name: str) bool ΒΆ
Removes a named visualization of a path for the given robot.
- Parameter
robot
: The robot associated with the path.
- Parameter
name
: The name of the path to be removed.
- Parameter
- reset(self: Studio) bool ΒΆ
Resets the environment to the state before a trajectory or events were run. In particular, it removes all obstacles there were added dynamically.
- run_action(self: Studio, action: Action) bool ΒΆ
Run the given action in Jacobi Studio.
- Parameter
action
: The action to be run.
- Returns:
Was the action successfully sent to Studio?
- Parameter
- run_events(self: Studio, events: Events) bool ΒΆ
Run the events at the specified timings in Jacobi Studio.
- Parameter
events
: The events to be run at the specified timings.
- Parameter
- run_trajectories(self: Studio, trajectories: list[tuple[Trajectory, Robot]], events: Events = Studio.Events(), loop_forever: bool = False) bool ΒΆ
Runs multiple trajectories for different robots in parallel, alongside the events at the specified timings. Optionally, the visualization can be looped.
- Parameter
trajectories
: Pairs of trajectories per robot to be run.
- Parameter
events
: The events to be run at the specified timings.
- Parameter
loop_forever
: Whether to loop the visualization forever.
- Parameter
- run_trajectory(self: Studio, trajectory: Trajectory, events: Events = Studio.Events(), loop_forever: bool = False, robot: Robot = None) bool ΒΆ
Runs a trajectory for the given robot (or the last active robot) in Jacobi Studio, alongside the events at the specified timings. Optionally, the visualization can be looped.
- Parameter
trajectory
: The trajectory to be run.
- Parameter
events
: The events to be run at the specified timings.
- Parameter
loop_forever
: Whether to loop the visualization forever.
- Parameter
robot
: Optional robot to run the trajectory for.
- Parameter
- set_camera_depth_map(self: Studio, depths: list[list[float]], x: float, y: float, camera: Camera = None) bool ΒΆ
Sets the depth map visualization of a camera.
- Parameter
depths
: The depth map data.
- Parameter
x
: Size of the depth map along the x-axis.
- Parameter
y
: Size of the depth map along the y-axis.
- Parameter
camera
: Optional camera associated with the depth map.
- Parameter
- set_camera_image_encoded(self: Studio, image: str, camera: Camera) bool ΒΆ
Sets an image for a camera encoded as a string.
- Parameter
image
: The encoded image to be set.
- Parameter
camera
: Optional camera associated with the image.
- Parameter
- set_camera_point_cloud(self: Studio, points: list[float], camera: Camera = None) bool ΒΆ
Sets the point cloud visualization of a camera.
- Parameter
points
: The point cloud data.
- Parameter
camera
: Optional camera associated with the point cloud.
- Parameter
- set_end_effector(self: Studio, obstacle: Obstacle | None, robot: Robot = None) bool ΒΆ
Sets the end-effector of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Parameter
- set_io_signal(self: Studio, name: str, value: int | float, robot: Robot = None) bool ΒΆ
Sets an I/O signal of the given robot, or the last active robot instead.
- Parameter
name
: The name of the I/O signal.
- Parameter
value
: The value to be set for the I/O signal.
- Parameter
robot
: Optional robot associated with the I/O signal.
- Parameter
- set_item(self: Studio, obstacle: Obstacle | None, robot: Robot = None) bool ΒΆ
Sets the item obstacle of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Parameter
- set_joint_position(self: Studio, joint_position: list[float], robot: Robot = None) bool ΒΆ
Sets the joint position of the given robot, or the last active robot instead.
- Parameter
joint_position
: The desired joint position.
- Parameter
robot
: Optional robot to set the joint position for.
- Parameter
- set_material(self: Studio, material: str, robot: Robot = None) bool ΒΆ
Sets the material of the given robot, or the last active robot instead.
- Parameter
material
: The material to be set.
- Parameter
robot
: Optional robot associated with the material.
- Parameter
- update_camera(self: Studio, camera: Camera) bool ΒΆ
Updates the camera with the same name in Jacobi Studio.
- Parameter
camera
: The camera to be updated.
- Parameter
- update_obstacle(self: Studio, obstacle: Obstacle) bool ΒΆ
Updates the obstacle with the same name.
- Parameter
obstacle
: The obstacle to be updated.
- Parameter
- property is_connectedΒΆ
Whether the library is connected to Studio Live
- Returns:
Whether the library is connected to Studio Live.
- property portΒΆ
Port of the websocket connection
- property speedupΒΆ
A factor to speed up or slow down running trajectories or events.
- class jacobi.Studio.ActionΒΆ
Bases:
pybind11_object
An action that can be performed in Jacobi Studio.
The Action class represents an action in Jacobi Studio, such as setting a robotβs joint position, adding an obstacle, or manipulating the environment. An action can contain multiple commands, allowing for complex interactions in Studio.
- __init__(*args, **kwargs)ΒΆ
- class jacobi.Studio.EventsΒΆ
Bases:
pybind11_object
A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).
The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.
- __init__(self: Events) None ΒΆ
A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).
The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.
- static add_camera(camera: Camera) Action ΒΆ
Returns an action that adds a camera.
- Parameter
camera
: The camera to be added.
- Returns:
The action to add the camera.
- Parameter
- static add_obstacle(obstacle: Obstacle) Action ΒΆ
Returns an action that adds the given obstacle to the environment.
- Parameter
obstacle
: The obstacle to be added.
- Returns:
The action to add the obstacle.
- Parameter
- static add_robot(robot: Robot) Action ΒΆ
Returns an action that adds the given robot to the environment.
- Parameter
robot
: The robot to be added.
- Returns:
The action to add the robot.
- Parameter
- static add_robot_path(points: list[list[float]], robot: Robot = None, name: str = '', color: str = '', stroke: float = -1.0, arrow_size: float = 1.0) Action ΒΆ
Returns an action that adds a visualization of a path for the given robot.
- Parameter
points
: The points defining the path.
- Parameter
robot
: Optional robot associated with the path.
- Parameter
name
: Optional name for the path.
- Parameter
color
: Optional color for the path visualization.
- Parameter
stroke
: Optional stroke width for the path visualization.
- Parameter
arrow_size
: Optional size of arrow for end of path
- Returns:
The action to add the robot path visualization.
- Parameter
- static add_waypoint(point: list[float] | Waypoint | CartesianWaypoint | jacobi.MultiRobotPoint | Region | CartesianRegion) Action ΒΆ
Returns an action that adds the given Cartesian waypoint to the environment.
- Parameter
point
: The Cartesian waypoint to be added.
- Returns:
The action to add the Cartesian waypoint.
- Parameter
- static remove_camera(camera: Camera) Action ΒΆ
Returns an action that removes a camera.
- Parameter
camera
: The camera to be removed.
- Returns:
The action to remove the camera.
- Parameter
- static remove_obstacle(obstacle: Obstacle) Action ΒΆ
Returns an action that removes the given obstacle (by name) from the environment.
- Parameter
obstacle
: The obstacle to be removed.
- Returns:
The action to remove the obstacle.
- Parameter
- static remove_robot_path(robot: Robot, name: str) Action ΒΆ
Returns an action that removes a visualization of a named path for the given robot.
- Parameter
robot
: The robot associated with the path.
- Parameter
name
: The name of the path to be removed.
- Returns:
The action to remove the robot path visualization.
- Parameter
- static set_camera_depth_map(depths: list[list[float]], x: float, y: float, camera: Camera = None) Action ΒΆ
Returns an action that sets the depth map visualization of a camera.
- Parameter
depths
: The depth map data.
- Parameter
x
: Size of the depth map along the x-axis.
- Parameter
y
: Size of the depth map along the y-axis.
- Parameter
camera
: Optional camera associated with the depth map.
- Returns:
The action to set the camera depth map.
- Parameter
- static set_camera_image_encoded(image: str, camera: Camera) Action ΒΆ
Returns an action that sets an image for a camera encoded as a string.
- Parameter
image
: The encoded image to be set.
- Parameter
camera
: Optional camera associated with the image.
- Returns:
The action to set the camera image.
- Parameter
- static set_end_effector(obstacle: Obstacle | None, robot: Robot = None) Action ΒΆ
Returns an action that sets the end-effector obstacle of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Returns:
The action to set the item obstacle.
- Parameter
- static set_io_signal(name: str, value: int | float, robot: Robot = None) Action ΒΆ
Returns an action that sets an I/O signal of the given robot, or the last active robot instead.
- Parameter
name
: The name of the I/O signal.
- Parameter
value
: The value to be set for the I/O signal.
- Parameter
robot
: Optional robot associated with the I/O signal.
- Returns:
The action to set the I/O signal.
- Parameter
- static set_item(obstacle: Obstacle | None, robot: Robot = None) Action ΒΆ
Returns an action that sets the item obstacle of the given robot, or the last active robot instead.
- Parameter
obstacle
: Optional obstacle to be set.
- Parameter
robot
: Optional robot associated with the obstacle.
- Returns:
The action to set the item obstacle.
- Parameter
- static set_joint_position(joint_position: list[float], robot: Robot = None) Action ΒΆ
Returns an action that sets the joint position of the given robot, or the last active robot instead.
- Parameter
joint_position
: The desired joint position.
- Parameter
robot
: Optional robot to set the joint position for.
- Returns:
The action to set the joint position.
- Parameter
- static set_material(material: str, robot: Robot = None) Action ΒΆ
Returns an action that sets the material of the given robot, or the last active robot instead.
- Parameter
material
: The material to be set.
- Parameter
robot
: Optional robot associated with the material.
- Returns:
The action to set the material.
- Parameter
CameraΒΆ
- class jacobi.IntrinsicsΒΆ
Bases:
pybind11_object
Intrinsics of a camera
Represents the intrinsic parameters of a camera, which include the focal lengths, optical center coordinates, and image dimensions.
- __init__(self: Intrinsics, focal_length_x: float, focal_length_y: float, optical_center_x: float, optical_center_y: float, width: int, height: int) None ΒΆ
- as_matrix(self: Intrinsics) numpy.ndarray[numpy.float64] ΒΆ
- property focal_length_xΒΆ
The focal length along the x-axis [px]
- property focal_length_yΒΆ
The focal length along the y-axis [px]
- property heightΒΆ
The image height [px]
- property optical_center_xΒΆ
The x-coordinate of the optical center [px]
- property optical_center_yΒΆ
The y-coordinate of the optical center [px]
- property widthΒΆ
The image width [px]
- class jacobi.CameraΒΆ
Bases:
Element
Camera element
The Camera class extends the Element class and includes parameters for the camera model and its intrinsic properties. The class allows for specifying the cameraβs model name, its intrinsics, and its position in 3D space.
- __init__(self: Camera, model: str, name: str, origin: Frame, intrinsics: Intrinsics) None ΒΆ
Default constructor.
- property intrinsicsΒΆ
The camera intrinsics
- property modelΒΆ
The model name of the camera