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
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 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.
-
virtual std::shared_ptr<Robot> clone() const = 0ΒΆ
-
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::YaskawaGP180120, 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.
-
enumerator AnalyticΒΆ
-
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].
-
enum class InverseKinematicsMethodΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
class Arm : public jacobi::RobotArmΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
-
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 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.
-
virtual std::shared_ptr<Robot> clone() const overrideΒΆ
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 theRobotArm
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.
-
enumerator RevoluteΒΆ
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 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::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.
-
enum class JointTypeΒΆ