Robots

class Robot : public std::enable_shared_from_this<Robot>

The Robot class represents a robot arm or a collection of robot arms.

The Robot class is an abstract class that represents a robot arm or a collection of robot arms. It provides a minimal interface for planning, including methods for forward kinematics and serialization.

Subclassed by jacobi::RobotArm, jacobi::robots::DualArm, jacobi::robots::TripleArm

Public Functions

virtual std::shared_ptr<Robot> clone() const = 0

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual std::optional<double> get_control_rate() const = 0

Retrieves the control rate of the robot.

Returns:

An optional double representing the control rate (in Hz) of the robot. If not available, the method will return std::nullopt.

virtual size_t get_degrees_of_freedom() const = 0

Retrieves the degrees of freedom of the robot.

Returns:

The degrees of freedom (DOFs) or number of axes of the robot.

virtual Config get_position() const = 0

Retrieves the current position of the robot.

Returns:

A Config object representing the current joint positions of the robot.

virtual Config get_min_position() const = 0

Retrieves the minimum position limits of the robot.

Returns:

A Config object representing the minimum joint position limits of the robot.

virtual Config get_max_position() const = 0

Retrieves the maximum position limits of the robot.

Returns:

A Config object representing the maximum joint position limits of the robot.

virtual Config get_max_velocity() const = 0

Retrieves the maximum velocity limits of the robot.

Returns:

A Config object representing the maximum joint velocity limits of the robot.

virtual Config get_max_acceleration() const = 0

Retrieves the maximum acceleration limits of the robot.

Returns:

A Config object representing the maximum joint acceleration limits of the robot.

virtual Config get_max_jerk() const = 0

Retrieves the maximum jerk limits of the robot.

Returns:

A Config object representing the maximum joint jerk limits of the robot.

virtual void forward_position(const Config &q) = 0

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) = 0

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) = 0

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual void set_base(const Frame &base, const Frame &parent = Frame::Identity())

Sets the origin (base frame) of the robot.

Parameters:
  • base – The Frame representing the new base or origin of the robot.

  • parent – An optional Frame representing the parent frame. Defaults to the identity frame.

Frame base() const

The origin of the robot’s base.

Returns:

A Frame representing the current origin of the robot base.

virtual void set_speed(double speed) = 0

Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.

Parameters:

speed – A double representing the speed to be set for the robot.

Public Members

size_t id = {1024}

ID of the robot obstacles.

std::string model

The model name of the robot.

std::string name

The name (id) of the robot arm.

Public Static Functions

static std::shared_ptr<Robot> from_model(const std::string &model)

Returns the robot with the given model name.

Parameters:

model – A std::string representing the model specification.

Returns:

A std::shared_ptr<Robot> pointing to the created Robot.

class RobotArm : public jacobi::Robot

Subclassed by jacobi::robots::ABBIRB1200590, jacobi::robots::ABBIRB1200770, jacobi::robots::ABBIRB1300714, jacobi::robots::ABBIRB1600612, jacobi::robots::ABBIRB260012185, jacobi::robots::ABBIRB460060205, jacobi::robots::ABBIRB6700150320, jacobi::robots::ABBYuMiIRB14000::Arm, jacobi::robots::CustomRobot, jacobi::robots::FanucLR10iA10, jacobi::robots::FanucLRMate200iD7L, jacobi::robots::FanucM20iB25, jacobi::robots::FanucM710iC45M, jacobi::robots::FrankaPanda, jacobi::robots::KinovaGen37DoF, jacobi::robots::KukaIiwa7, jacobi::robots::KukaKR6R700sixx, jacobi::robots::KukaKR70R2100, jacobi::robots::MecademicMeca500, jacobi::robots::UfactoryXArm7, jacobi::robots::UniversalUR10, jacobi::robots::UniversalUR10e, jacobi::robots::UniversalUR20, jacobi::robots::UniversalUR5e, jacobi::robots::YaskawaGP12, jacobi::robots::YaskawaGP180, jacobi::robots::YaskawaGP50, jacobi::robots::YaskawaHC10, jacobi::robots::YaskawaHC20

Public Types

enum class InverseKinematicsMethod

The inverse kinematics method to use.

Values:

enumerator Analytic

Analytic inverse kinematics.

enumerator Numeric

Numeric inverse kinematics.

enumerator URAnalytic

Universal Robots Analytic inverse kinematics.

using Jacobian = Eigen::Matrix<double, 6, Eigen::Dynamic>

The Jacobian matrix type for the robot arm.

Public Functions

inline virtual std::optional<double> get_control_rate() const override

Retrieves the control rate of the robot.

inline virtual size_t get_degrees_of_freedom() const override

Retrieves the degrees of freedom of the robot.

Returns:

The degrees of freedom (DOFs) or number of axes of the robot.

inline virtual Config get_position() const override

Retrieves the current position of the robot.

Returns:

A Config object representing the current joint positions of the robot.

inline virtual Config get_min_position() const override

Retrieves the minimum position limits of the robot.

Returns:

A Config object representing the minimum joint position limits of the robot.

inline virtual Config get_max_position() const override

Retrieves the maximum position limits of the robot.

Returns:

A Config object representing the maximum joint position limits of the robot.

inline virtual Config get_max_velocity() const override

Retrieves the maximum velocity limits of the robot.

Returns:

A Config object representing the maximum joint velocity limits of the robot.

inline virtual Config get_max_acceleration() const override

Retrieves the maximum acceleration limits of the robot.

Returns:

A Config object representing the maximum joint acceleration limits of the robot.

inline virtual Config get_max_jerk() const override

Retrieves the maximum jerk limits of the robot.

Returns:

A Config object representing the maximum joint jerk limits of the robot.

inline std::optional<Obstacle> end_effector_obstacle() const

Get the (optional) obstacle attached to the robot’s flange.

Returns:

An (optional) obstacle attached to the robot’s flange.

void set_end_effector_obstacle(const std::optional<Obstacle> &end_effector)

Set the (optional) obstacle attached to the robot’s flange.

Parameters:

item – An (optional) obstacle attached to the robot’s flange.

inline std::optional<Obstacle> item_obstacle() const

Get the (optional) obstacle attached to the robot’s TCP.

Returns:

An (optional) Obstacle attached to the robot’s TCP.

void set_item_obstacle(const std::optional<Obstacle> &item)

Set the (optional) obstacle attached to the robot’s TCP.

Parameters:

item – An (optional) Obstacle attached to the robot’s TCP.

virtual void set_speed(double speed) override

Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.

Parameters:

speed – A double representing the speed to be set for the robot.

virtual void set_base(const Frame &base, const Frame &parent = Frame::Identity()) override

Sets the origin (base frame) of the robot.

Parameters:
  • base – The Frame representing the new base or origin of the robot.

  • parent – An optional Frame representing the parent frame. Defaults to the identity frame.

inline Frame flange_to_tcp() const

The transformation from the robot’s flange to the robot’s TCP.

Returns:

A Frame representing the transformation from the robot’s flange to the robot’s TCP.

void set_flange_to_tcp(const Frame &flange_to_tcp)

Sets the transformation from the robot’s flange to the robot’s TCP.

Parameters:

flange_to_tcp – A Frame representing the transformation from the robot’s flange to the robot’s TCP.

inline Frame world_base() const

Retrieves the frame of the robot’s base.

Returns:

A Frame representing the frame of the robot’s base.

inline Frame flange() const

Retrieves the frame of the robot’s flange.

Returns:

A Frame representing the frame of the robot’s flange.

inline Frame tcp() const

Retrieves the frame of the robot’s TCP.

Returns:

A Frame representing the frame of the robot’s TCP.

inline virtual Frame tcp_position() const

Retrieves the frame of the robot’s TCP.

Returns:

A Frame representing the frame of the robot’s TCP.

inline virtual Twist tcp_velocity() const

Retrieves the Cartesian velocity of the robot’s TCP.

Returns:

A Twist representing the Cartesian velocity of the robot’s TCP.

inline virtual Twist tcp_acceleration() const

Retrieves the Cartesian acceleration of the robot’s TCP.

Returns:

A Twist representing the Cartesian acceleration of the robot’s TCP.

Frame calculate_tcp(const Config &joint_position)

Calculates the forward_kinematics and returns the frame of the robot’s TCP.

Parameters:

joint_position – The joint position of the robot.

Returns:

The frame of the robot’s TCP.

double calculate_tcp_speed(const Config &joint_position, const Config &joint_velocity)

Calculates the forward_kinematics and returns the norm of the Cartesian velocity of the robot’s TCP.

Parameters:
  • joint_position – The joint position of the robot.

  • joint_velocity – The joint velocity of the robot.

Returns:

The Cartesian speed of the TCP.

virtual Jacobian calculate_jacobian() const = 0

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

Public Members

const size_t degrees_of_freedom

The degrees of freedom (or number of axis) of the robot.

const size_t number_joints

The number of joints with links in between.

const Config default_position

The default robot position - used for initializing the current robot position.

Config position

The current (or last) position of the robot used for planning. Mostly relevant for multi-robot planning.

std::optional<double> control_rate

The (optional) default control rate. [Hz].

The obstacles for each robot link.

Config min_position

Minimum position for each joint. [rad].

Config max_position

Maximum position for each joint. [rad].

Config max_velocity

Maximum absolute velocity for each joint. [rad/s].

Config max_acceleration

Maximum absolute acceleration for each joint. [rad/s^2].

Config max_jerk

Maximum absolute jerk for each joint. [rad/s^3].

class DualArm : public jacobi::Robot

Subclassed by jacobi::robots::ABBYuMiIRB14000

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual std::optional<double> get_control_rate() const override

Retrieves the control rate of the robot.

Returns:

An optional double representing the control rate (in Hz) of the robot. If not available, the method will return std::nullopt.

virtual size_t get_degrees_of_freedom() const override

Retrieves the degrees of freedom of the robot.

Returns:

The degrees of freedom (DOFs) or number of axes of the robot.

virtual Config get_position() const override

Retrieves the current position of the robot.

Returns:

A Config object representing the current joint positions of the robot.

virtual Config get_min_position() const override

Retrieves the minimum position limits of the robot.

Returns:

A Config object representing the minimum joint position limits of the robot.

virtual Config get_max_position() const override

Retrieves the maximum position limits of the robot.

Returns:

A Config object representing the maximum joint position limits of the robot.

virtual Config get_max_velocity() const override

Retrieves the maximum velocity limits of the robot.

Returns:

A Config object representing the maximum joint velocity limits of the robot.

virtual Config get_max_acceleration() const override

Retrieves the maximum acceleration limits of the robot.

Returns:

A Config object representing the maximum joint acceleration limits of the robot.

virtual Config get_max_jerk() const override

Retrieves the maximum jerk limits of the robot.

Returns:

A Config object representing the maximum joint jerk limits of the robot.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual void set_base(const Frame &base, const Frame &parent = Frame::Identity()) override

Helper methods.

virtual void set_speed(double speed) override

Sets the velocity, acceleration, and jerk limits to a factor [0, 1] of their respective default (maximum) values.

Parameters:

speed – A double representing the speed to be set for the robot.

virtual void to_json(nlohmann::json &j) const override

Serialization.

Public Members

std::shared_ptr<RobotArm> left

The left arm of the robot.

std::shared_ptr<RobotArm> right

The right arm of the robot.

class ABBIRB1200590 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class ABBIRB1300714 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class ABBIRB1600612 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class ABBIRB460060205 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class ABBIRB6700150320 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class ABBYuMiIRB14000 : public jacobi::robots::DualArm
class Arm : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class FanucLR10iA10 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class FanucLRMate200iD7L : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class FanucM20iB25 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class FanucM710iC45M : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class FrankaPanda : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class KinovaGen37DoF : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class KukaIiwa7 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class MecademicMeca500 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class UfactoryXArm7 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class UniversalUR5e : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class UniversalUR10 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class UniversalUR10e : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class UniversalUR20 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class YaskawaGP12 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class YaskawaGP50 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class YaskawaHC10 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

class YaskawaHC20 : public jacobi::RobotArm

Public Functions

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

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 CustomRobot : public jacobi::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.

Public Types

enum class JointType

Types of joints that can be present in the robot.

Values:

enumerator Revolute

A revolute joint that allows rotation.

enumerator Continuous

A continuous joint that allows unlimited rotation.

enumerator Prismatic

A prismatic joint that allows linear motion.

enumerator Fixed

A fixed joint that does not allow any motion.

Public Functions

explicit CustomRobot(size_t degrees_of_freedom)

Constructs a CustomRobot with a specified degrees of freedom.

Parameters:

degrees_of_freedom – The degrees of freedom for the robot.

explicit CustomRobot(size_t degrees_of_freedom, size_t number_joints)

Constructs a CustomRobot with a specified degrees of freedom and joints.

Parameters:
  • degrees_of_freedom – The degrees of freedom for the robot.

  • number_joints – The number of joints in the robot.

virtual std::shared_ptr<Robot> clone() const override

Clones the current robot.

Returns:

A shared pointer to a new instance of the robot that is a copy of the current one.

virtual void forward_position(const Config &q) override

Computes the forward kinematics for the given joint positions.

Parameters:

q – A Config object representing the joint positions of the robot.

virtual void forward_velocity(const Config &q, const Config &dq) override

Computes the forward kinematics for the given joint positions and velocities.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

virtual void forward_acceleration(const Config &q, const Config &dq, const Config &ddq) override

Computes the forward kinematics for the given joint positions, velocities, and accelerations.

Parameters:
  • q – A Config object representing the joint positions of the robot.

  • dq – A Config object representing the joint velocities of the robot.

  • ddq – A Config object representing the joint accelerations of the robot.

virtual Jacobian calculate_jacobian() const override

Calculates the Jacobian of the current robot’s kinematics.

Returns:

The Jacobi matrix representing the derivative of robot’s TCP over the joint space

inline virtual size_t get_degrees_of_freedom() const override

Retrieves the degrees of freedom of the robot.

Returns:

The degrees of freedom (DOFs) or number of axes of the robot.

inline virtual Config get_position() const override

Retrieves the current position of the robot.

Returns:

A Config object representing the current joint positions of the robot.

inline virtual Config get_min_position() const override

Retrieves the minimum position limits of the robot.

Returns:

A Config object representing the minimum joint position limits of the robot.

inline virtual Config get_max_position() const override

Retrieves the maximum position limits of the robot.

Returns:

A Config object representing the maximum joint position limits of the robot.

inline virtual Config get_max_velocity() const override

Retrieves the maximum velocity limits of the robot.

Returns:

A Config object representing the maximum joint velocity limits of the robot.

inline virtual Config get_max_acceleration() const override

Retrieves the maximum acceleration limits of the robot.

Returns:

A Config object representing the maximum joint acceleration limits of the robot.

inline virtual Config get_max_jerk() const override

Retrieves the maximum jerk limits of the robot.

Returns:

A Config object representing the maximum joint jerk limits of the robot.

inline virtual Frame tcp_position() const override

Retrieves the frame of the robot’s TCP.

Returns:

A Frame representing the frame of the robot’s TCP.

inline virtual Twist tcp_velocity() const override

Retrieves the Cartesian velocity of the robot’s TCP.

Returns:

A Twist representing the Cartesian velocity of the robot’s TCP.

inline virtual Twist tcp_acceleration() const override

Retrieves the Cartesian acceleration of the robot’s TCP.

Returns:

A Twist representing the Cartesian acceleration of the robot’s TCP.

std::optional<Config> inverse_kinematics(const CartesianWaypoint &waypoint)

Computes the inverse kinematics for a Cartesian waypoint.

Parameters:

waypoint – The Cartesian waypoint to compute the inverse kinematics for.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const Config &reference_config)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

std::optional<Config> inverse_kinematics(const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

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.

Parameters:
  • tcp – The Cartesian position to compute the inverse kinematics for.

  • reference_config – The reference configuration to use for the inverse kinematics.

Returns:

An optional Config object representing the joint positions of the robot.

Public Members

std::shared_ptr<RobotArm> child

Possible child robot.

The translations between the links.

std::vector<std::array<double, 3>> joint_axes

Axes of the joints in the robot.

std::vector<JointType> joint_types

The type of the joints: Currently revolute, continuous, prismatic, and fixed joints are supported.

std::vector<std::string> joint_names

Names of the joints in the robot.

std::vector<std::string> config_joint_names

Names of the joints corresponding to a specific joint configuration.

Public Static Functions

static std::shared_ptr<CustomRobot> load_from_urdf_file(const std::filesystem::path &file, const std::string &base_link = "base_link", const std::string &end_link = "flange")

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.

Parameters:
  • file – The path to the URDF file.

  • base_link – The name of the base link in the URDF.

  • end_link – The name of the end link in the URDF.

Returns:

A shared pointer to the loaded robot.