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.