C++ΒΆ

GeometryΒΆ

using Config = std::vector<double>

Type alias for std::vector<double> as a joint configuration of a robot.

struct Frame : public Eigen::Isometry3d

Represents a transformation or pose in 3D Cartesian space.

Encapsulates translation and rotation in a unified manner for 3D poses.

Public Types

using Translation = Eigen::Translation3d

Translation component.

using EulerAngles = Eigen::EulerAngles<double, Eigen::EulerSystemXYZ>

Euler angles representation.

using EulerParameter = std::array<double, 6>

Euler angles and translation.

using QuaternionParameter = std::array<double, 7>

Quaternion and translation.

Public Functions

Frame()

Default constructor.

Frame(const Eigen::Isometry3d &frame)

Construct a Frame from an Eigen Isometry3d object.

Parameters:

frame – An Eigen Isometry3d object representing the transformation.

double translational_distance(const Frame &other) const

Calculate the Euclidean distance between two Frames’ positions.

Parameters:

other – The other Frame to compare against.

Returns:

double The Euclidean distance.

double angular_distance(const Frame &other) const

Calculate the angular distance between two Frames’ orientations.

Parameters:

other – The other Frame to compare against.

Returns:

double The angular distance.

Frame interpolate(double t, const Frame &other) const

Interpolate between this Frame and another Frame.

Parameters:
  • t – The interpolation parameter (0.0 to 1.0).

  • other – The other Frame to interpolate towards.

Returns:

Frame The interpolated Frame.

std::array<double, 16> to_matrix() const

Convert the Frame to a 4x4 matrix.

Returns:

std::array<double, 16> The Frame as a 4x4 matrix.

std::array<double, 6> to_euler() const

Convert the Frame to Euler angles and translation.

Returns:

std::array<double, 6> The Frame as Euler angles and translation.

bool operator==(const Frame &other) const

Check if two Frames are equal.

Parameters:

other – The other Frame to compare against.

Returns:

bool True if the Frames are equal, false otherwise.

Public Static Functions

static Frame Identity()

Get the identity transformation.

Returns:

Frame The identity Frame.

static Frame from_matrix(const std::array<double, 16> &data)

Create a Frame from a matrix.

Parameters:

data – A 16-element array representing a 4x4 matrix.

Returns:

Frame The Frame constructed from the matrix.

static Frame from_translation(double x, double y, double z)

Create a Frame from translation values.

Parameters:
  • x – The x translation.

  • y – The y translation.

  • z – The z translation.

Returns:

Frame The Frame with the specified translation.

static Frame from_quaternion(double x, double y, double z, double qw, double qx, double qy, double qz)

Create a Frame from quaternion values.

Parameters:
  • x – The x component of the quaternion.

  • y – The y component of the quaternion.

  • z – The z component of the quaternion.

  • qw – The scalar component of the quaternion.

  • qx – The x component of the quaternion.

  • qy – The y component of the quaternion.

  • qz – The z component of the quaternion.

Returns:

Frame The Frame with the specified quaternion.

static Frame from_euler(double x, double y, double z, double a, double b, double c)

Create a Frame from Euler angles.

Parameters:
  • x – The x translation.

  • y – The y translation.

  • z – The z translation.

  • a – The rotation angle around the x-axis.

  • b – The rotation angle around the y-axis.

  • c – The rotation angle around the z-axis.

Returns:

Frame The Frame with the specified translation and Euler angles.

static Frame x(double x)

Create a Frame representing a translation along the x-axis.

Parameters:

x – The translation value along the x-axis.

Returns:

Frame The Frame with the x-axis translation.

static Frame y(double y)

Create a Frame representing a translation along the y-axis.

Parameters:

y – The translation value along the y-axis.

Returns:

Frame The Frame with the y-axis translation.

static Frame z(double z)

Create a Frame representing a translation along the z-axis.

Parameters:

z – The translation value along the z-axis.

Returns:

Frame The Frame with the z-axis translation.

static Frame Rx(double c, double s)

Create a Frame representing a rotation around the x-axis.

Parameters:
  • c – The cosine of the rotation angle.

  • s – The sine of the rotation angle.

Returns:

Frame The Frame with the rotation around the x-axis.

static Frame Ry(double c, double s)

Create a Frame representing a rotation around the y-axis.

Parameters:
  • c – The cosine of the rotation angle.

  • s – The sine of the rotation angle.

Returns:

Frame The Frame with the rotation around the y-axis.

static Frame Rz(double c, double s)

Create a Frame representing a rotation around the z-axis.

Parameters:
  • c – The cosine of the rotation angle.

  • s – The sine of the rotation angle.

Returns:

Frame The Frame with the rotation around the z-axis.

static Frame Rx(double a)

Create a Frame representing a rotation around the x-axis.

Parameters:

a – The rotation angle around the x-axis.

Returns:

Frame The Frame with the rotation around the x-axis.

static Frame Ry(double a)

Create a Frame representing a rotation around the y-axis.

Parameters:

a – The rotation angle around the y-axis.

Returns:

Frame The Frame with the rotation around the y-axis.

static Frame Rz(double a)

Create a Frame representing a rotation around the z-axis.

Parameters:

a – The rotation angle around the z-axis.

Returns:

Frame The Frame with the rotation around the z-axis.

struct Twist : public Eigen::Vector<double, 6>

Represents a velocity in 3D Cartesian space.

The Twist struct represents a 6-dimensional vector used to describe velocity in 3D Cartesian space. It consists of linear velocities in the x, y, and z directions, and angular velocities around these axes.

Public Functions

Twist()

Default constructor.

Twist(double x, double y, double z, double rx, double ry, double rz)

Construct a Twist with specified linear and angular velocities.

Parameters:
  • x – The linear velocity along the x-axis.

  • y – The linear velocity along the y-axis.

  • z – The linear velocity along the z-axis.

  • rx – The angular velocity around the x-axis.

  • ry – The angular velocity around the y-axis.

  • rz – The angular velocity around the z-axis.

Twist(const std::array<double, 6> &twist)

Construct a Twist from an array.

Parameters:

twist – An array containing the 6-dimensional twist values.

Twist(const Eigen::Vector<double, 6> &twist)

Construct a Twist from an Eigen vector.

Parameters:

twist – An Eigen vector containing the 6-dimensional twist values.

Twist operator+(const Twist &other)

Add two Twist objects.

Parameters:

other – The Twist object to add.

Returns:

Twist The result of the addition.

Twist transform(const Eigen::Matrix3d &rotation, const Eigen::Vector3d &translation) const

Transform the Twist by a rotation and translation.

Parameters:
  • rotation – A 3x3 rotation matrix.

  • translation – A 3D translation vector.

Returns:

Twist The transformed Twist.

Twist cross(const Twist &other) const

Compute the cross product of two Twists.

Parameters:

other – The Twist object to cross with this one.

Returns:

Twist The result of the cross product.

std::array<double, 6> to_array() const

Convert the Twist to an array.

Converts the Twist object into a 6-element array, with the components arranged as [x, y, z, rx, ry, rz].

Returns:

std::array<double, 6> The Twist represented as an array.

ElementΒΆ

struct Element

The base element of a scene.

The Element struct represents the base element of a scene, such as a robot, camera, or obstacle. It contains a name, pose, and tags that can be used to identify and categorize the element.

Subclassed by jacobi::Camera, jacobi::CartesianRegion, jacobi::CartesianWaypoint, jacobi::Obstacle, jacobi::Region, jacobi::Waypoint

Public Functions

bool has_tag(const std::string &tag) const

Checks whether a tag is present on the element. Tags are case-insensitive.

Parameters:

tag – The tag to check for.

Returns:

bool True if the tag is present, false otherwise.

std::optional<std::string> get_parameter(const std::string &tag) const

Reads the value of a tag parameter param=value. Tags are case-insensitive.

Parameters:

tag – The tag to read the parameter from.

Returns:

std::optional<std::string> The value of the parameter if it exists, std::nullopt otherwise.

Public Members

std::string name

The unique name of the element, for display and identification.

Frame origin = {Frame::Identity()}

Pose of the element, relative to the parent. Is called β€œbase” for robots in Studio.

std::vector<std::string> tags

Given tags of the element, might be with a parameter param=value.

WaypointsΒΆ

class Waypoint : public jacobi::Element

A joint-space waypoint with possible position, velocity, and/or acceleration values.

The Waypoint class represents a point in the joint space of a robot with associated position, velocity, and acceleration values.

Public Functions

Waypoint(std::initializer_list<double> data)

Construct a waypoint by position data.

Parameters:

data – A list of position values to initialize the waypoint.

Waypoint(const Config &position)

Construct a waypoint with given position and zero velocity and acceleration.

Parameters:

position – The joint position to initialize the waypoint.

explicit Waypoint(const Config &position, const Config &velocity)

Construct a waypoint with given position and velocity and zero acceleration.

Parameters:
  • position – The joint position to initialize the waypoint.

  • velocity – The joint velocity to initialize the waypoint.

inline explicit Waypoint(const Config &position, const Config &velocity, const Config &acceleration)

Construct a waypoint with given position, velocity, and acceleration.

Parameters:
  • position – The joint position to initialize the waypoint.

  • velocity – The joint velocity to initialize the waypoint.

  • acceleration – The joint acceleration to initialize the waypoint.

inline explicit Waypoint(size_t size)

Construct a zero-initialized waypoint with the given size.

Parameters:

size – The degrees of freedom for the waypoint.

inline explicit Waypoint()

Construct an empty waypoint.

inline void append(const Waypoint &other)

Append another waypoint to this one.

This method concatenates the position, velocity, and acceleration data from another waypoint to this one.

Parameters:

other – The waypoint to append to this one.

inline size_t size() const

Get the size (or degrees of freedom) of the waypoint.

Returns:

size_t The degrees of freedom represented by the waypoint.

bool is_within(const Waypoint &other) const

Check if this waypoint is within another waypoint.

This method checks if the current waypoint’s position, velocity, and acceleration are within the respective boundaries of another waypoint.

Parameters:

other – The waypoint to compare against.

Returns:

true If this waypoint is within the boundaries of the other.

Returns:

false If this waypoint is not within the boundaries of the other.

Public Members

Config position

The joint position at the waypoint.

Config velocity

The joint velocity at the waypoint.

Config acceleration

The joint acceleration at the waypoint.

class CartesianWaypoint : public jacobi::Element

A Cartesian-space waypoint with possible position, velocity, and/or acceleration values.

The CartesianWaypoint class represents a point in Cartesian space with associated position, velocity, and acceleration frames. It is used to define the robot state in Cartesian space at a specific instance, with optional reference joint positions for inverse kinematics.

Public Functions

CartesianWaypoint(const Frame &position, const std::optional<Config> &reference_config = std::nullopt)

Construct a Cartesian waypoint with given position and zero velocity and acceleration.

Parameters:
  • position – The position frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

explicit CartesianWaypoint(const Frame &position, const Frame &velocity, const std::optional<Config> &reference_config = std::nullopt)

Construct a Cartesian waypoint with given position and velocity and zero acceleration.

Parameters:
  • position – The position frame to initialize the waypoint.

  • velocity – The velocity frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

explicit CartesianWaypoint(const Frame &position, const Frame &velocity, const Frame &acceleration, const std::optional<Config> &reference_config = std::nullopt)

Construct a Cartesian waypoint with given position, velocity, and acceleration.

Parameters:
  • position – The position frame to initialize the waypoint.

  • velocity – The velocity frame to initialize the waypoint.

  • acceleration – The acceleration frame to initialize the waypoint.

  • reference_config – An optional joint configuration for inverse kinematics.

explicit CartesianWaypoint()

Default constructor.

bool is_within(const CartesianWaypoint &other) const

Check if this Cartesian waypoint is within another Cartesian waypoint.

This method checks if the current waypoint’s position, velocity, and acceleration frames are within the respective boundaries of another CartesianWaypoint.

Parameters:

other – The CartesianWaypoint to compare against.

Returns:

true If this waypoint is within the boundaries of the other.

Returns:

false If this waypoint is not within the boundaries of the other.

bool is_within(const Waypoint &other, std::shared_ptr<RobotArm> robot) const

Check if this Cartesian waypoint is within a joint-space waypoint, given a specific robot arm.

This method checks if the current CartesianWaypoint’s position, velocity, and acceleration frames are within the boundaries of a joint space waypoint, considering the robot arm’s kinematics.

Parameters:
  • other – The joint-space Waypoint to compare against.

  • robot – The robot arm associated with the joint-space waypoint.

Returns:

true If this CartesianWaypoint is within the boundaries of the other joint-space waypoint.

Returns:

false If this CartesianWaypoint is not within the boundaries of the other joint-space waypoint.

Public Members

Frame position = {Frame::Identity()}

Frame of the position.

Frame velocity = {Frame::Identity()}

Frame of the velocity.

Frame acceleration = {Frame::Identity()}

Frame of the acceleration.

std::optional<Config> reference_config

An optional joint position that is used as a reference for inverse kinematics.

class Region : public jacobi::Element

A joint-space region with possible position, velocity, and/or acceleration values.

The Region class defines a region in joint space with boundaries on position, velocity, and acceleration. It is used to specify an area within which a the robot end-effector operates. The class provides methods to construct the region with varying levels of detail and to check if a given waypoint falls within the region’s boundaries.

Public Functions

explicit Region()

Default constructor.

explicit Region(const Config &min_position, const Config &max_position)

Construct a Region with position boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

explicit Region(const Config &min_position, const Config &max_position, const Config &min_velocity, const Config &max_velocity)

Construct a Region with position and velocity boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

explicit Region(const Config &min_position, const Config &max_position, const Config &min_velocity, const Config &max_velocity, const Config &min_acceleration, const Config &max_acceleration)

Construct a Region with position, velocity, and acceleration boundaries.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • min_acceleration – The minimum acceleration boundary.

  • max_acceleration – The maximum acceleration boundary.

inline size_t size() const

Get the size (or degrees of freedom) of the region.

Returns:

size_t The degrees of freedom represented by the region.

bool is_within(const Waypoint &other) const

Check if a given waypoint is within the region.

This method checks if the given waypoint’s position, velocity, and acceleration fall within the respective boundaries defined by the region.

Parameters:

other – The waypoint to check.

Returns:

true If the waypoint is within the region’s boundaries.

Returns:

false If the waypoint is not within the region’s boundaries.

Public Members

Config min_position

Minimum position boundary of the region.

Config max_position

Maximum position boundary of the region.

Config min_velocity

Minimum velocity boundary of the region.

Config max_velocity

Maximum velocity boundary of the region.

Config min_acceleration

Minimum acceleration boundary of the region.

Config max_acceleration

Maximum acceleration boundary of the region.

struct CartesianRegionBound

The min or max boundary of a Cartesian region.

The CartesianRegionBound struct represents the boundaries of a region in Cartesian space. It defines both positional (x, y, z) and orientational (gamma, alpha) limits. These boundaries are used to constrain the movement or state of an object within a specified region.

Public Functions

inline CartesianRegionBound()

Default constructor.

inline explicit CartesianRegionBound(double x, double y, double z, double gamma = 0.0, double alpha = 0.0)

Construct a CartesianRegionBound with specified values.

Parameters:
  • x – The x-coordinate of the boundary.

  • y – The y-coordinate of the boundary.

  • z – The z-coordinate of the boundary.

  • gamma – The rotational component around the z-axis (yaw).

  • alpha – The rotational component around the x-axis (roll).

Public Members

double x = {0.0}

The x-coordinate of the boundary.

double y = {0.0}

The y-coordinate of the boundary.

double z = {0.0}

The z-coordinate of the boundary.

double gamma = {0.0}

The rotational component around the z-axis (yaw).

double alpha = {0.0}

The rotational component around the x-axis (roll).

class CartesianRegion : public jacobi::Element

A Cartesian-space region with possible minimum and maximum position, velocity, and/or acceleration values.

The CartesianRegion class defines a region in Cartesian space with optional boundaries for position, velocity, and acceleration. It is used to describe constraints on a Cartesian region within which the robot end-effector operates. The region can also have an associated reference configuration.

Public Functions

CartesianRegion()

Default constructor.

explicit CartesianRegion(const Frame &origin)

Construct a CartesianRegion with a specified origin.

Parameters:

origin – The frame of reference for the region.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const std::optional<Config> &reference_config = std::nullopt)

Construct a CartesianRegion with position boundaries and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • reference_config – An optional reference configuration.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const CartesianRegionBound &min_velocity, const CartesianRegionBound &max_velocity, const std::optional<Config> &reference_config = std::nullopt)

Construct a CartesianRegion with position and velocity boundaries, and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • reference_config – An optional reference configuration.

explicit CartesianRegion(const CartesianRegionBound &min_position, const CartesianRegionBound &max_position, const CartesianRegionBound &min_velocity, const CartesianRegionBound &max_velocity, const CartesianRegionBound &min_acceleration, const CartesianRegionBound &max_acceleration, const std::optional<Config> &reference_config = std::nullopt)

Construct a CartesianRegion with position, velocity, and acceleration boundaries, and an optional reference configuration.

Parameters:
  • min_position – The minimum position boundary.

  • max_position – The maximum position boundary.

  • min_velocity – The minimum velocity boundary.

  • max_velocity – The maximum velocity boundary.

  • min_acceleration – The minimum acceleration boundary.

  • max_acceleration – The maximum acceleration boundary.

  • reference_config – An optional reference configuration.

bool is_within(const CartesianWaypoint &other) const

Check if a CartesianWaypoint is within the region.

Parameters:

other – The CartesianWaypoint to check.

Returns:

true If the waypoint is within the region.

Returns:

false If the waypoint is not within the region.

bool is_within(const Waypoint &other, std::shared_ptr<RobotArm> robot) const

Check if a Waypoint is within the region, given a specific robot arm.

Parameters:
  • other – The Waypoint to check.

  • robot – The robot arm associated with the waypoint.

Returns:

true If the waypoint is within the region.

Returns:

false If the waypoint is not within the region.

Public Members

CartesianRegionBound min_position

Minimum position boundary of the region.

CartesianRegionBound max_position

Maximum position boundary of the region.

CartesianRegionBound min_velocity

Minimum velocity boundary of the region.

CartesianRegionBound max_velocity

Maximum velocity boundary of the region.

CartesianRegionBound min_acceleration

Minimum acceleration boundary of the region.

CartesianRegionBound max_acceleration

Maximum acceleration boundary of the region.

std::optional<Config> reference_config

Reference configuration for the region, if any.

using MultiRobotPoint = std::map<std::shared_ptr<Robot>, std::variant<Config, Waypoint, CartesianWaypoint>>

A type for specifying an exact start or goal point per robot.

using Point = std::variant<Config, Waypoint, CartesianWaypoint, MultiRobotPoint, Region, CartesianRegion>

All types for specifying motion start or goals, either exact or by region.

using ExactPoint = std::variant<Config, Waypoint, CartesianWaypoint, MultiRobotPoint>

All types for specifying exact start or goal points.

ObstaclesΒΆ

struct Box

A box collision object.

The Box struct represents a simple 3D rectangular collision object. It is defined by its dimensions along the x, y, and z axes, which correspond to the width, depth, and height of the box, respectively.

Public Functions

inline explicit Box(float x, float y, float z)

Construct a box of size x, y, z along the respective axes.

Parameters:
  • x – The width of the box along the x-axis.

  • y – The depth of the box along the y-axis.

  • z – The height of the box along the z-axis.

inline explicit Box()

Default constructor.

Public Members

float x

Dimensions of the box [m].

struct Capsule

A capsule collision object.

The Capsule struct represents a simple 3D collision object shaped like a capsule (a cylinder with hemispherical ends). It is defined by its radius and length along the z-axis. Capsules are commonly used in collision detection due to their computational efficiency.

Public Functions

inline explicit Capsule(float radius, float length)

Construct a capsule with the given radius and length.

Parameters:
  • radius – The radius of the capsule.

  • length – The length of the capsule along the z-axis.

inline explicit Capsule()

Default constructor.

Public Members

float radius

Radius of the capsule [m].

float length

Length of the capsule along the z-axis [m].

struct Convex

A convex mesh collision object.

The Convex struct represents a 3D convex mesh, often used for collision detection. It supports loading from files, direct vertex and triangle specification, and provides utility functions like bounding box computation.

Public Functions

explicit Convex()

Default constructor.

explicit Convex(const std::filesystem::path &path, std::optional<float> scale)

Construct a convex object by loading from a file.

Parameters:
  • path – The path to the file (*.obj).

  • scale – Optional scale to apply when loading the object.

explicit Convex(uintptr_t vertices_buffer, size_t size)

Construct a convex object using a buffer of vertices.

This constructor is primarily used for WebAssembly (Wasm) bindings, where the vertex data is provided directly as a buffer.

Parameters:
  • vertices_buffer – Pointer to the buffer containing vertex data.

  • size – Number of vertices in the buffer.

explicit Convex(const std::vector<std::array<float, 3>> &verts, const std::vector<std::array<size_t, 3>> &triangs)

Construct a convex object from given vertices and triangles.

Parameters:
  • verts – List of vertex positions.

  • triangs – List of triangles, each defined by three vertex indices.

std::array<double, 3> get_bounding_box_minimum() const

Get the minimum bounding box corner.

Returns:

A 3D vector representing the minimum corner of the bounding box.

std::array<double, 3> get_bounding_box_maximum() const

Get the maximum bounding box corner.

Returns:

A 3D vector representing the maximum corner of the bounding box.

Public Members

std::optional<FileReference> file_reference

Optional file reference from which the convex object was loaded.

std::vector<Vector> vertices

List of vertices that define the convex mesh.

std::vector<Triangle> triangles

List of triangles that define the convex mesh surface.

Public Static Functions

static std::vector<Convex> load_from_file(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)

Load convex objects from a file.

Parameters:
  • path – The path to the file (*.obj).

  • scale – Optional scale to apply when loading the object.

Returns:

A vector of Convex objects loaded from the file.

static Convex reference_studio_file(const std::filesystem::path &path, std::optional<float> scale = std::nullopt)

Create a reference to a Studio file.

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

  • scale – Optional scale to apply when referencing the file.

Returns:

A Convex object that references the specified Studio file.

Public Static Attributes

static std::filesystem::path base_path

Base path for file operations.

class Triangle
struct Cylinder

A cylinder collision object.

The Cylinder struct represents a 3D cylindrical collision object. It is defined by its radius and length along the z-axis.

Public Functions

inline explicit Cylinder(float radius, float length)

Construct a cylinder with the given radius and length.

Parameters:
  • radius – The radius of the cylinder.

  • length – The length of the cylinder along the z-axis.

inline explicit Cylinder()

Default constructor.

Public Members

float radius

Radius of the cylinder [m].

float length

Length of the cylinder along the z-axis [m].

struct Sphere

A sphere collision object.

The Sphere struct represents a 3D spherical collision object, defined by its radius, which determines its size in all directions.

Public Functions

inline explicit Sphere(float radius)

Construct a sphere with the given radius.

Initializes the sphere with the specified radius.

Parameters:

radius – The radius of the sphere.

inline explicit Sphere()

Default constructor.

Public Members

float radius

Radius of the sphere [m].

class Obstacle : public jacobi::Element

An environment obstacle.

The Obstacle class represents an object in an environment that can be used for both visualization and collision detection. Obstacles can have various geometric shapes and properties, and can be associated with a robot or be independent within the environment.

Public Functions

explicit Obstacle()

Default constructor.

Obstacle with_origin(const Frame &origin) const

Clone the current obstacle and set the new origin.

Creates a copy of the current obstacle and updates its origin to the provided frame. This function is useful for creating modified versions of an obstacle without altering the original object.

Parameters:

origin – The new pose (origin) for the cloned obstacle.

Returns:

Obstacle A new Obstacle instance with the updated origin.

Public Members

Color color

The hex-string representation of the obstacle’s color, without the leading #.

This string defines the color of the obstacle for visualization purposes, formatted as a hex code (e.g., β€œFF5733” for orange).

std::optional<FileReference> visual

Optional reference to the visual file.

This optional reference points to an external visual file that represents the obstacle. If provided, this file will be used for rendering the obstacle’s appearance.

Geometry collision

The object for collision checking (and/or visualization).

This variant holds the geometric representation of the obstacle. It can be any of the supported shapes, including Box, Capsule, Convex, ConvexVector, Cylinder, DepthMap, or Sphere.

bool for_visual = {true}

Whether this obstacle is used for visualization.

If true, the obstacle will be rendered in the environment’s visualization in Studio. By default, this is set to true.

bool for_collision = {true}

Whether this obstacle is used for collision checking.

If true, the obstacle will be considered in collision detection calculations. By default, this is set to true.

float safety_margin = {0.0}

An additional obstacle-specific safety margin for collision checking (on top of the environment’s global safety margin).

This margin adds an extra buffer around the obstacle during collision detection. It is specific to this obstacle and is added on top of any global safety margins.

Robot *robot = {nullptr}

Pointer to the associated robot, if any.

EnvironmentΒΆ

class Environment

The environment a robot (or multiple robots) lives in.

The Environment class manages static obstacles, collision checking, waypoints, cameras, and robots within a defined environment. The class provides methods to add, remove, and manage obstacles and waypoints, as well as to retrieve information about these elements. It also includes functionality for collision checking and updating the state of obstacles and robots.

Public Functions

explicit Environment(std::shared_ptr<Robot> robot, float safety_margin = 0.0)

Create an environment with a controllable robot.

Parameters:
  • robot – The robot to add to the environment.

  • safety_margin – The global safety margin for collision checking [m].

explicit Environment(const std::set<std::shared_ptr<Robot>> &robots, float safety_margin = 0.0)

Create an environment with multiple robots.

Parameters:
  • robots – The robots to add to the environment.

  • safety_margin – The global safety margin for collision checking [m].

float get_safety_margin() const

Environment’s global safety margin for collision checking [m].

Returns:

The global safety margin for collision checking [m].

std::shared_ptr<Robot> get_robot(const std::string &name = "") const

Get the robot with the given name from the environment.

In case there is only a single robot in the environment, the default empty name argument will return this robot. Otherwise throws an error if no robot with the name exists.

Parameters:

name – The name of the robot to retrieve.

Returns:

The shared pointer to a robot object associated with the given name.

std::vector<std::shared_ptr<Robot>> get_robots() const

Get all robots within the environment.

Returns:

A vector of shared pointers to the robots within the environment.

Point get_waypoint(const std::string &name) const

Get the waypoint with the given name from the environment. Throws an error if no waypoint with the name exists.

Parameters:

name – The name of the waypoint to retrieve.

Returns:

The waypoint associated with the given name.

std::optional<Point> get_waypoint_by_tag(const std::string &tag) const

Get a waypoint within the environment given a tag. If multiple waypoints have the same tag, the first one to be found is returned.

Parameters:

tag – The tag associated with the waypoint to retrieve.

Returns:

An optional containing the waypoint associated with the given tag, or std::nullopt if no waypoint with the tag is found.

std::vector<Point> get_waypoints_by_tag(const std::string &tag) const

Get all waypoints within the environment given a tag.

Parameters:

tag – The tag associated with the waypoints to retrieve.

Returns:

A vector of waypoints that have the specified tag.

std::vector<Point> get_waypoints() const

Get all waypoints within the environment.

This function retrieves a list of all waypoints present in the environment.

Returns:

A vector of waypoints within the environment.

std::shared_ptr<Obstacle> get_obstacle(const std::string &name) const

Get the obstacle with the given name from the environment. Throws an error if no obstacle with the name exists.

Parameters:

name – The name of the obstacle to retrieve.

Returns:

A shared pointer to the obstacle associated with the given name.

std::vector<std::shared_ptr<Obstacle>> get_obstacles_by_tag(const std::string &tag) const

Get all obstacles within the environment that carry the given tag.

Parameters:

tag – The tag associated with the obstacles to retrieve.

Returns:

A vector of shared pointers to the obstacles that have the specified tag.

std::vector<std::shared_ptr<Obstacle>> get_obstacles() const

Get all obstacles within the environment.

This function retrieves a list of all obstacles present in the environment.

Returns:

A vector of shared pointers to the obstacles within the environment.

std::shared_ptr<Camera> get_camera(const std::string &name = "") const

Get a camera from the environment.

Parameters:

name – Optional parameter to specify the name of the camera. If not provided, an empty string defaults to retrieving a camera without a specific name.

Returns:

A shared pointer to the camera associated with the given name, or a default camera if the name is empty.

std::shared_ptr<Obstacle> add_obstacle(std::shared_ptr<Obstacle> obstacle)

Add an obstacle to the environment (and returns the pointer to it)

Parameters:

obstacle – The obstacle to add to the environment.

Returns:

The original shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Obstacle &obstacle)

Add an obstacle to the environment (and returns the pointer to it)

Parameters:

obstacle – The obstacle to add to the environment.

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Box &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a box-shaped obstacle to the environment.

Parameters:
  • object – The box-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Capsule &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a capsule-shaped obstacle to the environment.

Parameters:
  • object – The capsule-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Convex &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a convex-shaped obstacle to the environment.

Parameters:
  • object – The convex-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const ConvexVector &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a vector of convex-shaped obstacles to the environment.

Parameters:
  • object – The vector of convex-shaped obstacles to add.

  • origin – The initial pose of the obstacles in the environment (default is Frame::Identity()).

  • color – The color of the obstacles in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacles (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Cylinder &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a cylinder-shaped obstacle to the environment.

Parameters:
  • object – The cylinder-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const DepthMap &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a depth map-shaped obstacle to the environment.

Parameters:
  • object – The depth map-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const Sphere &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a sphere-shaped obstacle to the environment.

Parameters:
  • object – The sphere-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const Box &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add an obstacle with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The obstacle to add (of a specific type, e.g., Box, Capsule, etc.).

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const Capsule &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Overload for adding an obstacle with a name and various shapes.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The obstacle to add (of a specific type, e.g., Capsule, Convex, etc.).

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const Convex &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a convex-shaped obstacle with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The convex-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const ConvexVector &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a vector of convex-shaped obstacles with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The vector of convex-shaped obstacles to add.

  • origin – The initial pose of the obstacles in the environment (default is Frame::Identity()).

  • color – The color of the obstacles in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacles (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const Cylinder &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a cylinder-shaped obstacle with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The cylinder-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const DepthMap &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a depth map-shaped obstacle with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The depth map-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

std::shared_ptr<Obstacle> add_obstacle(const std::string &name, const Sphere &object, const Frame &origin = Frame::Identity(), const Obstacle::Color &color = "000000", float safety_margin = 0.0)

Add a sphere-shaped obstacle with a name to the environment.

Parameters:
  • name – The name to assign to the obstacle.

  • object – The sphere-shaped obstacle to add.

  • origin – The initial pose of the obstacle in the environment (default is Frame::Identity()).

  • color – The color of the obstacle in hexadecimal format (default is β€œ000000”).

  • safety_margin – The safety margin around the obstacle (default is 0.0).

Returns:

A shared pointer to the added obstacle.

void remove_obstacle(const std::shared_ptr<Obstacle> &obstacle)

Removes the given obstacles from the environment and from all collision checking.

Parameters:

obstacle – The obstacle to remove from the environment.

void remove_obstacle(const std::string &name)

Removes all obstacles with the given name from the environment and from all collision checking.

Parameters:

name – The name of the obstacle to remove from the environment.

void update_fixed_obstacles()

Updates all fixed obstacles for the internal collision checking. This should be called after changing e.g. the position or size of an obstacle.

void update_depth_map(const std::shared_ptr<Obstacle> &obstacle)

Updates the depths matrix of a given depth map obstacle for the internal collision checking.

Parameters:

obstacle – The obstacle to update the depths map for.

void update_joint_position(const std::shared_ptr<Robot> &robot, const Config &joint_position)

Updates the joint position of the given robot for the internal collision checking.

Parameters:
  • robot – The robot to update the joint position for.

  • joint_position – The new joint position to set for the robot.

bool check_collision(const std::shared_ptr<Robot> &robot, const Config &joint_position, CollisionDetail &detail)

Check if a joint position is in collision.

Parameters:
  • robot – The robot to check the joint position for.

  • joint_position – The joint position to check for collision.

  • detail – [out] The collision detail to fill in case of a collision.

Returns:

True if the joint position is in collision, false otherwise.

bool check_collision(const std::shared_ptr<Robot> &robot, const Config &joint_position)

Check if a joint position is in collision.

Parameters:
  • robot – The robot to check the joint position for.

  • joint_position – The joint position to check for collision.

Returns:

True if the joint position is in collision, false otherwise.

bool check_collision(const Config &joint_position)

Check if a joint position is in collision.

Parameters:

joint_position – The joint position to check for collision.

Returns:

True if the joint position is in collision, false otherwise.

bool check_collision(const std::shared_ptr<Robot> &robot, const CartesianWaypoint &waypoint)

Check if there exists a collision-free inverse kinematics for the Cartesian position.

Parameters:
  • robot – The robot to check the Cartesian position for.

  • waypoint – The Cartesian position to check for collision.

Returns:

True if there exists a collision-free inverse kinematics for the Cartesian position, false otherwise.

bool check_collision(const std::shared_ptr<Robot> &robot, const Frame &tcp, const std::optional<Config> &reference_config = std::nullopt)

Check if there exists a collision-free inverse kinematics for the given robot and end-effector pose.

Parameters:
  • robot – The robot to check for collision-free inverse kinematics.

  • tcp – The end-effector pose (transformation) to check for collision.

  • reference_config – Optional reference configuration for inverse kinematics of the end-effector pose.

Returns:

True if there exists a collision-free inverse kinematics for the given end-effector pose, false otherwise.

bool check_collision(const CartesianWaypoint &waypoint)

Check if there exists a collision-free inverse kinematics for the Cartesian position.

Parameters:

waypoint – The Cartesian position to check for collision.

Returns:

True if there exists a collision-free inverse kinematics for the Cartesian position, false otherwise.

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

Check if there exists a collision-free inverse kinematics for the given end-effector pose.

Parameters:
  • tcp – The end-effector pose to check for collision.

  • reference_config – Optional reference configuration for inverse kinematics of the end-effector pose.

Returns:

True if there exists a collision-free inverse kinematics for the given end-effector pose, false otherwise.

std::optional<Config> get_collision_free_joint_position_nearby(const Config &joint_position, const std::shared_ptr<Robot> &robot = nullptr)

Calculate a collision free joint position close to the reference position.

Parameters:
  • joint_position – The reference joint position to find a collision free joint position close to.

  • robot – The robot to find a collision free joint position for.

Returns:

An optional containing the collision free joint position close to the reference position, or std::nullopt if no such joint position exists.

Public Members

std::map<std::string, std::shared_ptr<Robot>> robots

All robots used for collision checking with default parameters.

std::map<std::string, Point> waypoints

All robots used for collision checking with default parameters.

std::vector<std::shared_ptr<Obstacle>> obstacles

All static obstacles in the environment, owning the data.

std::map<std::string, std::shared_ptr<Camera>> cameras

All cameras in the environment.

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.

MotionsΒΆ

struct LinearSection

Represents a linear Cartesian section for either the approach to the goal or the retraction from the start.

Public Types

enum class Approximation

Whether to approximate the Cartesian linear motion in joint space for singularity-free calculation.

Values:

enumerator Never
enumerator Always

Public Members

Frame offset

Relative linear cartesian offset from the reference pose.

double speed = {1.0}

Speed of the sub-motion, relative to the overall motion’s speed.

bool smooth_transition = {true}

Whether to use a smooth transition between this and the next or previous section. If false, the robot will come to a complete stop at the transition point.

class Motion

Represents a request for a collision-free point-to-point motion.

The Motion class provides an interface for general point-to-point motion planning with arbitrary waypoints, linear approach and retraction, and task constraints. It includes parameters for the motion name, robot, start and goal points, and additional settings for motion planning, such as collision checking and soft failure handling.

Public Functions

inline explicit Motion(const Point &start, const Point &goal)

Construct a Motion with a given start and goal point.

Parameters:
  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion(std::shared_ptr<Robot> robot, const Point &start, const Point &goal)

Construct a Motion with a name, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion(const std::string &name, const Point &start, const Point &goal)

Construct a Motion with a name, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

explicit Motion(const std::string &name, std::shared_ptr<Robot> robot, const Point &start, const Point &goal)

Construct a Motion with a name, robot, start and goal point.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit Motion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm associated with the motion.

bool is_within(std::shared_ptr<Robot> robot, const Waypoint &start_test, const Waypoint &goal_test) const

Check if the motion start and goal points are within the provided start and goal points.

Parameters:
  • start_test – The start point to compare against.

  • goal_test – The goal point to compare against.

Returns:

true If the motion start and goal points are within the provided start and goal points.

Returns:

false If the motion start and goal points are not within the provided start and goal points.

Public Members

std::string name

The unique name of the motion.

Point start

Start point of the motion.

Point goal

Goal point of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

bool ignore_collisions = {false}

Whether to ignore collisions.

std::vector<ExactPoint> waypoints

Intermediate waypoints that the motion passes through exactly. The list of waypoints is limited to less than four, otherwise please take a look at LowLevelMotion.

std::optional<LinearSection> linear_retraction

Optional relative linear cartesian motion for retracting from the start pose.

std::optional<LinearSection> linear_approach

Optional relative linear cartesian motion for approaching the goal pose.

bool soft_collision_start = {false}

Enables soft collision checking at the start of the motion. Then, the item obstacle of the robot is allowed to be in collision at the start point. The trajectory will move the item out of collision, and won’t allow a collision thereafter.

bool soft_collision_goal = {false}

Enables soft collision checking at the goal of the motion. Then, the item obstacle of the robot is allowed to be in collision at the goal point, but minimizes the time in collision and allows going into collision only once.

double path_length_loss_weight = {0.1}

Weight of the loss minimizing the path length of the trajectory.

double orientation_loss_weight = {0.0}

Weight of the loss minimizing the maximizing deviation of the end-effector orientation to the target value.

std::array<double, 3> orientation_target = {{0.0, 0.0, 1.0}}

Target vector pointing in the direction of the end-effector (TCP) orientation in the global coordinate system.

std::optional<double> cartesian_tcp_speed_cutoff

Optional Cartesian TCP speed (translation-only) cutoff. This is a post-processing step.

std::optional<std::vector<ExactPoint>> initial_waypoints

Optional initial waypoints to start the optimization with (don’t use with intermediate waypoints).

class LinearMotion

Represents a request for a linear Cartesian-space motion.

The LinearMotion struct represents a request for a linear motion in Cartesian space. It consists of a start and goal point, as well as a robot to perform the motion. It provides an interface for planning singularity-free linear motion in Cartesian space between any two waypoints.

Public Functions

inline explicit LinearMotion(const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given start, and goal.

Parameters:
  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion(std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given robot, start, and goal.

Parameters:
  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion(const std::string &name, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given name, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

explicit LinearMotion(const std::string &name, std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)

Construct a linear motion with a given name, robot, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • start – The start point of the motion.

  • goal – The goal point of the motion.

inline explicit LinearMotion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm for the motion.

Public Members

std::string name

The unique name of the motion.

ExactPoint start

Start point of the motion.

ExactPoint goal

Goal point of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

bool ignore_collisions = {true}

Whether to ignore collisions.

class LowLevelMotion

Represents a request for a low-level motion.

The LinearMotion class provides an interface for very efficient planning of motion between joint-space waypoints. While low level motions are not checked for collisions, they are much faster to compute and allow for more flexible constraints such as a minimum duration parameter. This motion type is suitable for visual servoing task or other real-time control.

Public Types

enum ControlInterface

The control interface for the motion, specifying either position or velocity control.

Values:

enumerator Position

Position-control: Full control over the entire kinematic state (Default)

enumerator Velocity

Velocity-control: Ignores the current position, target position, and velocity limits.

enum Synchronization

The synchronization strategy for the motion, specifying either phase, time, time if necessary, or no synchronization.

Values:

enumerator Phase

Phase synchronize the DoFs when possible, else fallback to β€œTime” strategy (Default)

enumerator Time

Always synchronize the DoFs to reach the target at the same time.

enumerator TimeIfNecessary

Synchronize only when necessary (e.g. for non-zero target velocity or acceleration)

enumerator None

Calculate every DoF independently.

enum DurationDiscretization

The duration discretization strategy for the motion, specifying either continuous or discrete durations.

Values:

enumerator Continuous

Every trajectory synchronization duration is allowed (Default)

enumerator Discrete

The trajectory synchronization duration must be a multiple of the control cycle.

Public Functions

inline explicit LowLevelMotion(std::shared_ptr<Robot> robot)

Construct a low-level motion with a given robot.

Parameters:

robot – The robot for the motion.

inline explicit LowLevelMotion(const std::string &name)

Construct a low-level motion with a given name.

Parameters:

name – The unique name of the motion.

explicit LowLevelMotion(const std::string &name, std::shared_ptr<Robot> robot)

Construct a low-level motion with a given name, robot, start, and goal.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

inline explicit LowLevelMotion()

Default constructor.

inline std::shared_ptr<RobotArm> robot_arm() const

The robot arm for the motion.

Public Members

std::string name

The unique name of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

Waypoint start

Start waypoint of the motion.

Waypoint goal

Goal waypoint of the motion.

std::vector<Config> intermediate_positions

List of intermediate positions.

For a small number of waypoints (less than 16), the trajectory goes exactly through the intermediate waypoints. For a larger number of waypoints, first a filtering algorithm is used to keep the resulting trajectory close to the original waypoints.

std::optional<double> minimum_duration

A minimum duration of the motion.

ControlInterface control_interface = {ControlInterface::Position}

The control interface for the motion.

Synchronization synchronization = {Synchronization::Phase}

The synchronization strategy for the motion.

DurationDiscretization duration_discretization = {DurationDiscretization::Continuous}

The duration discretization strategy for the motion.

class LinearPath : public jacobi::PathType

A path type for linear motion between two waypoints.

The LinearPath class implements the PathType interface to represent a linear path from a start pose to a goal pose. It calculates waypoints along a straight line between the two poses and supports serialization and deserialization to/from JSON.

Public Functions

inline LinearPath(const Frame &start, const Frame &goal)

Construct a LinearPath with a given start and goal pose.

Parameters:
  • start – The starting pose of the linear path.

  • goal – The ending pose of the linear path.

inline LinearPath()

Default constructor.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints for the linear motion.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

virtual bool operator!=(const PathType &rhs) const override

Compare two PathType objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the objects are not equal.

Returns:

false If the objects are equal.

Public Members

Frame start

The start pose of the linear path.

Frame goal

The goal pose of the linear path.

class CircularPath : public jacobi::PathType

A circular path type with a specified start pose, circle center, normal, and rotation angle, optionally maintaining tool-to-surface orientation.

The CircularPath class implements the PathType interface to represent a circular path with a given start pose, circle center, normal to the plane of the circle, and rotation angle. This path type optionally supports maintaining tool-to-surface orientation throughout the path.

Public Functions

inline CircularPath(const Frame &start, const double theta, const std::vector<double> &center, const std::vector<double> &normal, const bool keep_tool_to_surface_orientation = false)

Construct a CircularPath with a given start pose, rotation angle, circle center, normal, and optional tool-to-surface orientation.

Parameters:
  • start – The starting pose of the circular path.

  • theta – The rotation angle of the circular path in radians.

  • center – The center of the circle as a vector of doubles.

  • normal – The normal vector of the plane containing the circle.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

CircularPath(const Frame &start, const Frame &goal, const std::vector<double> &center, const bool keep_tool_to_surface_orientation = false)

Construct a CircularPath with a given start pose, goal pose, circle center, and optional tool-to-surface orientation. The rotation angle is inferred from the goal pose.

Parameters:
  • start – The starting pose of the circular path.

  • goal – The goal pose of the circular path (used to infer theta).

  • center – The center of the circle as a vector of doubles.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

inline CircularPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two CircularPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the CircularPath object is not equal to the provided PathType object.

Returns:

false If the CircularPath object is equal to the provided PathType object.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints for the circular motion.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

Public Members

Frame start

The start pose of the circular path.

double theta

The rotation angle of the circular path [rad].

std::vector<double> center

The center of the circle.

std::vector<double> normal

The normal of the plane in which to create a circular path.

bool keep_tool_to_surface_orientation

Whether to maintain the tool-to-surface orientation.

class BlendedPath : public jacobi::PathType

A path type for linear motion between waypoints with a circular blend to ensure motion continuity, optionally maintaining tool-to-surface orientation.

The BlendedPath class implements the PathType interface to represent a path that smoothly transitions between Cartesian waypoints with circular blends. This ensures continuity of motion. This path type optionally supports maintaining tool-to-surface orientation throughout the path.

Public Functions

inline BlendedPath(const PathWaypoints &waypoints, const double blend_radius, const bool keep_tool_to_surface_orientation = false)

Construct a BlendedPath with given waypoints, blend radius, and optional tool-to-surface orientation.

Parameters:
  • waypoints – The Cartesian waypoints defining the path.

  • blend_radius – The radius for the circular blend between waypoints.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

BlendedPath(const PathWaypoints &waypoints, const bool keep_tool_to_surface_orientation = false)

Construct a BlendedPath with given waypoints and optional tool-to-surface orientation. The blend radius is automatically calculated.

Parameters:
  • waypoints – The Cartesian waypoints defining the path.

  • keep_tool_to_surface_orientation – Whether to maintain tool-to-surface orientation.

inline BlendedPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two BlendedPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the BlendedPath object is not equal to the provided PathType object.

Returns:

false If the BlendedPath object is equal to the provided PathType object.

virtual PathWaypoints calculate_path(const double velocity, const double delta_time) override

Calculate the path waypoints with piecewise linear motion and circular blends.

Parameters:
  • velocity – The velocity used for path calculation.

  • delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

Public Members

PathWaypoints waypoints

The path Cartesian waypoints.

double blend_radius

The blend radius for the circular blend.

bool keep_tool_to_surface_orientation

Whether to maintain the tool-to-surface orientation.

class ArbitraryPath : public jacobi::PathType

A wrapper for a path with arbitrary user-provided waypoints.

The ArbitraryPath class implements the PathType interface and serves as a wrapper for a path defined by user-provided Cartesian waypoints. This class allows users to specify their own sequence of waypoints directly, without additional path calculations.

Public Functions

inline ArbitraryPath(const PathWaypoints &path)

Construct an ArbitraryPath with given waypoints.

Parameters:

path – The Cartesian waypoints defining the path.

inline ArbitraryPath()

Default constructor.

virtual bool operator!=(const PathType &rhs) const override

Compare two ArbitraryPath objects for inequality.

Parameters:

rhs – The PathType object to compare against.

Returns:

true If the ArbitraryPath object is not equal to the provided PathType object.

Returns:

false If the ArbitraryPath object is equal to the provided PathType object.

inline virtual PathWaypoints calculate_path(const double, const double) override

Return the user-provided waypoints as the calculated path.

Parameters:
  • velocity – The velocity used for path calculation (not utilized in this case).

  • delta_time – The time step used for path calculation (not utilized in this case).

Returns:

The waypoints provided by the user as the path.

Public Members

PathWaypoints path

The path Cartesian waypoints.

class PathFollowingMotion

Represents a request for a Cartesian-space motion to be followed by the end-effector.

The PathFollowingMotion class provides an interface for Cartesian-space paths to be accurately followed by the robot end-effector with a constant velocity. There are four different path types that are supported: linear, circular, blended and arbitrary. The path-following motion is suitable for use cases such as welding, painting, dispensing and deburring, where constant end-effector velocity is required for successful task execution. It includes parameters for the motion name, robot, path type, velocity, and additional settings for motion planning, such as collision checking and soft failure handling.

Public Functions

inline explicit PathFollowingMotion(std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a given path type and optional velocity.

Parameters:
  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline explicit PathFollowingMotion(const std::string &name, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a name, path type, and optional velocity.

Parameters:
  • name – The unique name of the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline explicit PathFollowingMotion(std::shared_ptr<Robot> robot, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a robot, path type, and optional velocity.

Parameters:
  • robot – The robot for the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

explicit PathFollowingMotion(const std::string &name, std::shared_ptr<Robot> robot, std::shared_ptr<PathType> path_type, const double velocity = 50.0)

Construct a PathFollowingMotion with a name, robot, path type, and optional velocity.

Parameters:
  • name – The unique name of the motion.

  • robot – The robot for the motion.

  • path_type – The Cartesian path type to follow.

  • velocity – The desired velocity of the end-effector [m/s]. If not provided, the robot will move as fast as possible while respecting velocity limits.

inline PathFollowingMotion()

Default constructor.

inline PathWaypoints calculate_path(const double delta_time)

Calculate the path waypoints based on the current feasible velocity and delta time.

Parameters:

delta_time – The time step used for path calculation.

Returns:

The calculated path waypoints as a sequence of Frames.

bool operator!=(const PathFollowingMotion &rhs) const

Compare two PathFollowingMotion objects for inequality.

Parameters:

rhs – The PathFollowingMotion object to compare against.

Returns:

true If the objects are not equal.

Returns:

false If the objects are equal.

Public Members

std::string name

The unique name of the motion.

std::shared_ptr<Robot> robot

The robot for the motion (e.g. defines the kinematics and the joint limits).

std::shared_ptr<PathType> path_type

The Cartesian path to follow.

double velocity = {50.0}

The desired velocity of the end-effector [m/s].

bool soft_failure = {true}

If true, the planner will adjust path velocity until a solution until velocity limits are satisfied.

bool check_collision = {true}

If true, the planner will check for collisions during the motion.

std::optional<Config> reference_config

Optional reference configuration for the start state of the motion.

double feasible_velocity = {50.0}

The feasible velocity of the end-effector achieved after planning [m/s] (only used if soft_failure is true).

Motion PlanningΒΆ

class Trajectory

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

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

Public Functions

inline explicit Trajectory(size_t dofs)

Create an empty trajectory with the given degrees of freedom.

Parameters:

dofs – The degrees of freedom of the joint space.

inline explicit Trajectory()

Default constructor.

inline size_t size() const

The number of time steps within the trajectory.

Returns:

The number of time steps within the trajectory.

State front() const

Access the first state at t=0 of the trajectory.

Returns:

The first state at t=0 of the trajectory.

State back() const

Access the last state at t=duration of the trajectory.

Returns:

The last state at t=duration of the trajectory.

void at_time(double time, Config &new_position, Config &new_velocity, Config &new_acceleration) const

Get the kinematic state at a given time. Make sure that the output arguments have enough memory.

Parameters:
  • time – The time at which to get the kinematic state.

  • new_position – [out] The joint position at the given time.

  • new_velocity – [out] The joint velocity at the given time.

  • new_acceleration – [out] The joint acceleration at the given time.

Config get_min_position() const

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

Returns:

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

Config get_max_position() const

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

Returns:

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

Config get_min_velocity() const

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

Returns:

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

Config get_max_velocity() const

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

Returns:

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

Config get_min_acceleration() const

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

Returns:

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

Config get_max_acceleration() const

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

Returns:

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

size_t get_step_closest_to(const Config &position) const

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

Returns:

size_t The step index of the closest position.

void update_first_position(const Config &joint_position)

Update the first position of the trajectory.

Parameters:

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

Trajectory reverse() const

Reverse the trajectory’s start and goal.

Returns:

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

void append(const Trajectory &other)

Append another trajectory to the current one.

Parameters:

other – The trajectory to append.

Trajectory &operator+=(const Trajectory &other)

Append another trajectory to the current one using the += operator.

Parameters:

other – The trajectory to append.

Returns:

Trajectory& Reference to the updated trajectory.

Trajectory slice(size_t start, size_t steps) const

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

Parameters:
  • start – The starting index of the slice.

  • steps – The number of steps to include in the slice.

Returns:

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

std::vector<Config> filter_path(const Config &max_distance) const

Filter a path of sparse waypoints from the trajectory.

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

Parameters:

max_distance – The maximum allowable distance between joint positions.

Returns:

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

std::string to_json() const

Serializes a trajectory to a json string.

void to_json_file(const std::filesystem::path &file) const

Saves a trajectory to a *.json file.

Parameters:

file – The path to the *.json file.

std::string as_table() const

To pretty print the trajectory as a table of positions.

Public Members

std::string id

Field for identifying trajectories (for the user)

std::string motion

Name of the motion this trajectory was planned for.

size_t degrees_of_freedom

The degrees of freedom (e.g. axis) of the trajectory.

double duration = {0.0}

The total duration in [s].

std::vector<double> times

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

std::vector<Config> positions

The joint positions along the trajectory.

std::vector<Config> velocities

The joint velocities along the trajectory.

std::vector<Config> accelerations

The joint accelerations along the trajectory.

Public Static Functions

static Trajectory from_json(const std::string &json)

Loads a trajectory from a json string.

static Trajectory from_json_file(const std::filesystem::path &file)

Loads a trajectory from a *.json file.

Parameters:

file – The path to the *.json file.

Returns:

Trajectory The loaded trajectory.

class Planner

Planning motions for robots.

The Planner class is is the core of the Jacobi Motion library. It is responsible for computing robot trajectories within a given environment. It provides various parameters for configuring the planning process, including resolution, optimization settings, and compute budgets. The class also supports loading and managing motion plans.

Public Functions

explicit Planner(std::shared_ptr<Environment> environment, double delta_time)

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

Parameters:
  • environment – The environment to plan the robot motions in.

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

explicit Planner(std::shared_ptr<Robot> robot, double delta_time)

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

Parameters:
  • robot – The robot to plan the motions for.

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

explicit Planner(std::shared_ptr<Environment> environment)

Create a planner with an environment.

Parameters:

environment – The environment to plan the robot motions in.

explicit Planner(std::shared_ptr<Robot> robot)

Create a planner with the robot inside an empty environment.

Parameters:

robot – The robot to plan the motions for.

void set_seed(std::optional<unsigned int> seed)

Set the seed of the planner’s random number generator.

Parameters:

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

void add_motion(const AnyMotion &motion)

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

Parameters:

motion – The motion to add, can be of any type.

AnyMotion get_motion(const std::string &name) const

Get a motion by its name.

Parameters:

name – The name of the motion to retrieve.

Returns:

The AnyMotion object associated with the given name.

void load_motion_plan(const std::filesystem::path &file)

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

Parameters:

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

std::optional<Trajectory> transfer_trajectory(const Trajectory &trajectory, const std::shared_ptr<RobotArm> &robot_from, const std::shared_ptr<RobotArm> &robot_to, const Frame &offset = Frame::Identity()) const

Transfers a trajectory from one robot to another.

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

Parameters:
  • trajectory – The trajectory to follow.

  • robot_from – The original robot to transfer from.

  • robot_to – The new robot to transfer to.

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

Returns:

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

std::optional<Trajectory> plan(const Config &start, const Config &goal)

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

Parameters:
  • start – The start configuration of the motion.

  • goal – The goal configuration of the motion.

Returns:

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

std::optional<Trajectory> plan(const Point &start, const Point &goal)

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

Parameters:
  • start – The start point of the motion.

  • goal – The goal point of the motion.

Returns:

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

std::optional<Trajectory> plan(const std::string &name, const std::optional<ExactPoint> &start = std::nullopt, const std::optional<ExactPoint> &goal = std::nullopt)

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

Parameters:
  • name – The name of the motion to plan.

  • start – The exact start position of the motion.

  • goal – The exact goal position of the motion.

Returns:

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

std::optional<Trajectory> plan(const Motion &motion, const std::optional<ExactPoint> &start = std::nullopt, const std::optional<ExactPoint> &goal = std::nullopt)

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

Parameters:
  • motion – The motion to plan.

  • start – The exact start position of the motion.

  • goal – The exact goal position of the motion.

Returns:

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

std::optional<Trajectory> plan(const LinearMotion &motion)

Plans a linear motion.

Parameters:

motion – The linear motion to plan.

Returns:

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

std::optional<Trajectory> plan(const LowLevelMotion &motion)

Plans a low-level motion.

Parameters:

motion – The low-level motion to plan.

Returns:

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

std::optional<Trajectory> plan(const PathFollowingMotion &motion)

Plans a path-following motion.

Parameters:

motion – The path-following motion to plan.

Returns:

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

std::optional<std::vector<Trajectory>> plan(const std::vector<AnyMotion> &motions)

Plans a feasible sequence of motions.

Parameters:

motions – The sequence of motions to plan.

Returns:

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

Public Members

std::shared_ptr<Environment> environment

The current environment to plan robot motions in.

double delta_time

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

Result last_calculation_result = {Result::Working}

Result of the last trajectory computation.

double last_calculation_duration = {0.0}

The calculation duration of the last full trajectory computation.

double pre_eps_steering = {1000.0}

Steering epsilon in the pre-planning stage [rad].

double pre_eps_collision = {3.33}

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

double pre_max_steps = {16 * 1024}

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

size_t pre_optimization_steps = {512}

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

double initial_perturbation_scale = {0.04}

Initial perturbation for the trajectory optimization.

size_t perturbation_change_steps = {256}

Steps without improvement after which the perturbation scale is adapted.

double perturbation_scale_change = {1e-2}

Change of the perturbation if no improvement could be found recently.

size_t max_optimization_steps = {5 * 1024}

Maximum number of optimization steps.

size_t max_break_steps = {1024}

Max number of steps without improvement before early stopping.

double meaningful_loss_improvement = {1e-2}

A meaningful relative improvement to avoid stopping.

std::optional<float> min_calculation_duration

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

std::optional<float> max_calculation_duration

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

Public Static Functions

static std::shared_ptr<Planner> load_from_project_file(const std::filesystem::path &file)

Loads a planner from a project file.

Parameters:

file – The path to the project file.

Returns:

A shared pointer to the loaded Planner object.

static std::shared_ptr<Planner> load_from_studio(const std::string &name)

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

Parameters:

name – The name of the Studio project.

Returns:

A shared pointer to the loaded Planner object.

Studio LiveΒΆ

class Studio

Helper class to connect and visualize trajectories and events in Jacobi Studio.

The Studio class provides functionality to connect to Jacobi Studio via a WebSocket, and to visualize trajectories and events. It manages the connection, handles incoming and outgoing messages, and allows the user to create and execute actions within Jacobi Studio.

Public Functions

explicit Studio(bool auto_connect = true, double timeout = 5.0)

Interface Jacobi Studio via code. Connects to Jacobi Studio automatically - please make sure to enable the Studio Live feature in the Jacobi Studio settings.

Parameters:
  • auto_connect – Whether to connect to Studio Live automatically.

  • timeout – The timeout for connecting to Studio Live.

inline void register_message_callback(const MessageCallback &callback)

Setup a callback for incoming message.

bool reconnect(double timeout = 5.0)

Reconnect to Studio Live.

Parameters:

timeout – The timeout for reconnecting to Studio Live.

Returns:

Whether the reconnection was successful.

bool is_connected() const

Whether the library is connected to Studio Live.

Returns:

Whether the library is connected to Studio Live.

bool run_action(const Action &action) const

Run the given action in Jacobi Studio.

Parameters:

action – The action to be run.

Returns:

Was the action successfully sent to Studio?

nlohmann::json get_from_action(const Action &action, const std::string &response_key)

Get an answer from Jacobi Studio.

Parameters:

action – The action to receive an answer for.

bool run_trajectory(const Trajectory &trajectory, const Events &events = {}, bool loop_forever = false, const std::shared_ptr<Robot> robot = nullptr) const

Runs a trajectory for the given robot (or the last active robot) in Jacobi Studio, alongside the events at the specified timings. Optionally, the visualization can be looped.

Parameters:
  • trajectory – The trajectory to be run.

  • events – The events to be run at the specified timings.

  • loop_forever – Whether to loop the visualization forever.

  • robot – Optional robot to run the trajectory for.

bool run_trajectories(const std::vector<std::pair<Trajectory, std::shared_ptr<Robot>>> &trajectories, const Events &events = {}, bool loop_forever = false) const

Runs multiple trajectories for different robots in parallel, alongside the events at the specified timings. Optionally, the visualization can be looped.

Parameters:
  • trajectories – Pairs of trajectories per robot to be run.

  • events – The events to be run at the specified timings.

  • loop_forever – Whether to loop the visualization forever.

bool run_events(const Events &events) const

Run the events at the specified timings in Jacobi Studio.

Parameters:

events – The events to be run at the specified timings.

inline bool set_joint_position(const Config &joint_position, const std::shared_ptr<Robot> robot = nullptr) const

Sets the joint position of the given robot, or the last active robot instead.

Parameters:
  • joint_position – The desired joint position.

  • robot – Optional robot to set the joint position for.

inline bool set_item(const std::optional<Obstacle> &obstacle, const std::shared_ptr<Robot> robot = nullptr) const

Sets the item obstacle of the given robot, or the last active robot instead.

Parameters:
  • obstacle – Optional obstacle to be set.

  • robot – Optional robot associated with the obstacle.

inline bool set_material(const std::string &material, const std::shared_ptr<Robot> robot = nullptr) const

Sets the material of the given robot, or the last active robot instead.

Parameters:
  • material – The material to be set.

  • robot – Optional robot associated with the material.

inline bool add_robot(const std::shared_ptr<Robot> &robot) const

Adds the given robot to the environment.

Parameters:

robot – The robot to be added.

inline bool add_robot_path(const std::vector<std::vector<double>> &points, const std::shared_ptr<Robot> robot = nullptr, const std::string &name = "", const std::string &color = "", float stroke = -1.0, float arrow_size = 1.0) const

Adds a visualization of a path for the given robot.

Parameters:
  • points – The points defining the path.

  • robot – Optional robot associated with the path.

  • name – Optional name for the path.

  • color – Optional color for the path visualization.

  • stroke – Optional stroke width for the path visualization.

  • arrow_size – Optional size of arrow for end of path

inline bool remove_robot_path(const std::shared_ptr<Robot> robot, const std::string &name) const

Removes a named visualization of a path for the given robot.

Parameters:
  • robot – The robot associated with the path.

  • name – The name of the path to be removed.

inline bool add_obstacle(const Obstacle &obstacle) const

Adds the given obstacle to the environment.

Parameters:

obstacle – The obstacle to be added.

inline bool add_waypoint(const Point &point) const

Adds the given Cartesian waypoint to the environment.

Parameters:

point – The Cartesian waypoint to be added.

inline bool update_obstacle(const Obstacle &obstacle) const

Updates the obstacle with the same name.

Parameters:

obstacle – The obstacle to be updated.

inline bool remove_obstacle(const Obstacle &obstacle) const

Removes the given obstacle (by name) from the environment.

Parameters:

obstacle – The obstacle to be removed.

inline bool set_io_signal(const std::string &name, std::variant<int, float> value, const std::shared_ptr<Robot> robot = nullptr) const

Sets an I/O signal of the given robot, or the last active robot instead.

Parameters:
  • name – The name of the I/O signal.

  • value – The value to be set for the I/O signal.

  • robot – Optional robot associated with the I/O signal.

inline bool set_camera_image_encoded(const std::string &image, const std::shared_ptr<Camera> camera = nullptr) const

Sets an image for a camera encoded as a string.

Parameters:
  • image – The encoded image to be set.

  • camera – Optional camera associated with the image.

inline bool set_camera_depth_map(const std::vector<std::vector<double>> &depths, float x, float y, const std::shared_ptr<Camera> camera = nullptr) const

Sets the depth map visualization of a camera.

Parameters:
  • depths – The depth map data.

  • x – The x-coordinate for the depth map.

  • y – The y-coordinate for the depth map.

  • camera – Optional camera associated with the depth map.

inline bool set_camera_point_cloud(const std::vector<double> &points, const std::shared_ptr<Camera> camera = nullptr) const

Sets the point cloud visualization of a camera.

Parameters:
  • points – The point cloud data.

  • camera – Optional camera associated with the point cloud.

inline bool add_camera(const std::shared_ptr<Camera> camera) const

Adds a camera in Jacobi Studio.

Parameters:

camera – The camera to be added.

inline bool update_camera(const std::shared_ptr<Camera> camera) const

Updates the camera with the same name in Jacobi Studio.

Parameters:

camera – The camera to be updated.

inline bool remove_camera(const std::shared_ptr<Camera> camera) const

Removes a camera in Jacobi Studio.

Parameters:

camera – The camera to be removed.

inline bool reset() const

Resets the environment to the state before a trajectory or events were run. In particular, it removes all obstacles there were added dynamically.

inline Config get_joint_position(const std::shared_ptr<Robot> robot = nullptr)

Get the joint position of a robot.

Parameters:

robot – Optional robot to get the joint position for.

Returns:

The joint position of the robot.

inline std::string get_camera_image_encoded(CameraStream stream, const std::shared_ptr<Camera> camera = nullptr)

Get an image from a camera encoded as a string.

Parameters:
  • stream – The type of camera stream to get.

  • camera – Optional camera to get the image from.

Returns:

The encoded image from the camera.

Public Members

std::string host = {"localhost"}

Host of the websocket connection.

int port = {8768}

Port of the websocket connection.

double speedup = {1.0}

A factor to speed up or slow down running trajectories or events.

class Action

An action that can be performed in Jacobi Studio.

The Action class represents an action in Jacobi Studio, such as setting a robot’s joint position, adding an obstacle, or manipulating the environment. An action can contain multiple commands, allowing for complex interactions in Studio.

struct Events : public std::multimap<double, Action>

A container that maps a specific timing to one or multiple actions. The static methods of this class do not change the visualization in Jacobi Studio immediately, but only return an action that can be executed later (e.g. alongside a trajectory).

The Events struct allows for scheduling actions in Jacobi Studio at specific times. Static methods are provided to create various actions, which can be executed later.

Public Static Functions

static inline Action set_joint_position(const Config &joint_position, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the joint position of the given robot, or the last active robot instead.

Parameters:
  • joint_position – The desired joint position.

  • robot – Optional robot to set the joint position for.

Returns:

The action to set the joint position.

static inline Action set_item(const std::optional<Obstacle> &obstacle, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the item obstacle of the given robot, or the last active robot instead.

Parameters:
  • obstacle – Optional obstacle to be set.

  • robot – Optional robot associated with the obstacle.

Returns:

The action to set the item obstacle.

static inline Action set_material(const std::string &material, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets the material of the given robot, or the last active robot instead.

Parameters:
  • material – The material to be set.

  • robot – Optional robot associated with the material.

Returns:

The action to set the material.

static inline Action add_robot(const std::shared_ptr<Robot> &robot)

Returns an action that adds the given robot to the environment.

Parameters:

robot – The robot to be added.

Returns:

The action to add the robot.

static inline Action add_robot_path(const std::vector<std::vector<double>> &points, const std::shared_ptr<Robot> robot = nullptr, const std::string &name = "", const std::string &color = "", float stroke = -1.0, float arrow_size = 1.0)

Returns an action that adds a visualization of a path for the given robot.

Parameters:
  • points – The points defining the path.

  • robot – Optional robot associated with the path.

  • name – Optional name for the path.

  • color – Optional color for the path visualization.

  • stroke – Optional stroke width for the path visualization.

  • arrow_size – Optional size of arrow for end of path

Returns:

The action to add the robot path visualization.

static inline Action remove_robot_path(const std::shared_ptr<Robot> robot, const std::string &name)

Returns an action that removes a visualization of a named path for the given robot.

Parameters:
  • robot – The robot associated with the path.

  • name – The name of the path to be removed.

Returns:

The action to remove the robot path visualization.

static inline Action add_obstacle(const Obstacle &obstacle)

Returns an action that adds the given obstacle to the environment.

Parameters:

obstacle – The obstacle to be added.

Returns:

The action to add the obstacle.

static inline Action add_waypoint(const Point &point)

Returns an action that adds the given Cartesian waypoint to the environment.

Parameters:

point – The Cartesian waypoint to be added.

Returns:

The action to add the Cartesian waypoint.

static inline Action update_obstacle(const Obstacle &obstacle)

Returns an action that updates the obstacle with the same name.

Parameters:

obstacle – The obstacle to be updated.

Returns:

The action to update the obstacle.

static inline Action remove_obstacle(const Obstacle &obstacle)

Returns an action that removes the given obstacle (by name) from the environment.

Parameters:

obstacle – The obstacle to be removed.

Returns:

The action to remove the obstacle.

static inline Action set_io_signal(const std::string &name, std::variant<int, float> value, const std::shared_ptr<Robot> robot = nullptr)

Returns an action that sets an I/O signal of the given robot, or the last active robot instead.

Parameters:
  • name – The name of the I/O signal.

  • value – The value to be set for the I/O signal.

  • robot – Optional robot associated with the I/O signal.

Returns:

The action to set the I/O signal.

static inline Action set_camera_image_encoded(const std::string &image, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets an image for a camera encoded as a string.

Parameters:
  • image – The encoded image to be set.

  • camera – Optional camera associated with the image.

Returns:

The action to set the camera image.

static inline Action set_camera_depth_map(const std::vector<std::vector<double>> &depths, float x, float y, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets the depth map visualization of a camera.

Parameters:
  • depths – The depth map data.

  • x – The x-coordinate for the depth map.

  • y – The y-coordinate for the depth map.

  • camera – Optional camera associated with the depth map.

Returns:

The action to set the camera depth map.

static inline Action set_camera_point_cloud(const std::vector<double> &points, const std::shared_ptr<Camera> camera = nullptr)

Returns an action that sets the point cloud visualization of a camera.

Parameters:
  • points – The point cloud data.

  • camera – Optional camera associated with the point cloud.

Returns:

The action to set the camera point cloud.

static inline Action add_camera(const std::shared_ptr<Camera> camera)

Returns an action that adds a camera.

Parameters:

camera – The camera to be added.

Returns:

The action to add the camera.

static inline Action update_camera(const std::shared_ptr<Camera> camera)

Returns an action that updates a camera with the same name.

Parameters:

camera – The camera to be updated.

Returns:

The action to update the camera.

static inline Action remove_camera(const std::shared_ptr<Camera> camera)

Returns an action that removes a camera.

Parameters:

camera – The camera to be removed.

Returns:

The action to remove the camera.