C++ΒΆ

GeometryΒΆ

using Config = std::vector<double>ΒΆ

Joint configuration of a robot.

class FrameΒΆ

Represents a transformation or pose in 3D Cartesian space.

static Frame Identity()ΒΆ
static Frame from_matrix(const std::array<double, 16> &data)ΒΆ
static Frame from_translation(double x, double y, double z)ΒΆ
static Frame from_quaternion(double x, double y, double z, double qw, double qx, double qy, double qz)ΒΆ
static Frame from_euler(double x, double y, double z, double a, double b, double c)ΒΆ

The angles a, b, c are using the extrinsic XYZ convention.

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

Flattened 4x4 matrix representation of the frame.

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

The angles a, b, c are using the extrinsic XYZ convention.

Frame inverse() constΒΆ

Calculate the inverse transformation of the frame.

double translational_distance(const Frame &other) constΒΆ

Calculates the Euclidian norm of the position difference.

double angular_distance(const Frame &other) constΒΆ

Calculates the angle of the rotational difference.

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

Calculates a spherical linear interpolation between this and the other frame at the interpolation parameter t.

class TwistΒΆ

Represents a velocity in 3D Cartesian space.

ElementΒΆ

class ElementΒΆ

The base element of a scene.

std::string nameΒΆ

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

std::vector<std::string> tagsΒΆ

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

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

Checks whether a tag is present on the element.

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

Reads the value of a tag parameter param=value.

WaypointsΒΆ

class Waypoint : ElementΒΆ

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

Config positionΒΆ

The joint position at the waypoint.

Config velocityΒΆ

The joint velocity at the waypoint.

Config accelerationΒΆ

The joint acceleration at the waypoint.

Waypoint(const Config &position)ΒΆ

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

Waypoint(const Config &position, const Config &velocity)ΒΆ

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

Waypoint(const Config &position, const Config &velocity, const Config &acceleration)ΒΆ

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

class CartesianWaypoint : ElementΒΆ

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

Frame positionΒΆ

Frame of the position.

Frame velocityΒΆ

Frame of the velocity.

Frame accelerationΒΆ

Frame of the acceleration.

std::optional<Config> reference_configΒΆ

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

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

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

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

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

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

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

class Region : ElementΒΆ

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

Config min_positionΒΆ
Config max_positionΒΆ
Config min_velocityΒΆ
Config max_velocityΒΆ
Config min_accelerationΒΆ
Config max_accelerationΒΆ
class CartesianRegionBoundΒΆ

The min or max boundary of a Cartesian region.

double xΒΆ

Translation along x-axis.

double yΒΆ

Translation along y-axis.

double zΒΆ

Translation along z-axis.

double gammaΒΆ

Euler angle around the global z-axis.

double alphaΒΆ

Angle from the global z-axis.

class CartesianRegion : ElementΒΆ

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

CartesianRegionBound min_positionΒΆ
CartesianRegionBound max_positionΒΆ
CartesianRegionBound min_velocityΒΆ
CartesianRegionBound max_velocityΒΆ
CartesianRegionBound min_accelerationΒΆ
CartesianRegionBound max_accelerationΒΆ
std::optional<Config> reference_configΒΆ

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

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ΒΆ

class BoxΒΆ

A box collision object.

float xΒΆ

Width of the box.

float yΒΆ

Depth of the box.

float zΒΆ

Height of the box.

Box(float x, float y, float z)ΒΆ

Construct a box of size x, y, z along the respective axis, corresponding to the width, depth, height of the box.

class CapsuleΒΆ

A capsule collision object.

float radiusΒΆ

Radius of the capsule.

float lengthΒΆ

Length of the capsule.

Capsule(float radius, float length)ΒΆ

Construct a capsule with the given radius and length. As a side note, a capsule is computationally efficient for collision checking.

class ConvexΒΆ

A convex mesh collision object.

std::optional<std::filesystem::path> file_pathΒΆ

The file path of the mesh object when loaded from a file.

std::array<double, 3> get_bounding_box_minimum()ΒΆ

The minimum position of the axis-aligned bounding box.

std::array<double, 3> get_bounding_box_maximum()ΒΆ

The maximum position of the axis-aligned bounding box.

static Convex load_from_file(const std::filesyste::path &path, std::optional<float> scale = std::nullopt)ΒΆ

Loads a mesh from a *.obj or *.stl file from the given path, and returns the convex hull of the mesh. If no scale is given, we automatically estimate the scale of the mesh to match base SI units e.g. [m].

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

Create a reference to a mesh file with the given filename already uploaded to a Studio project. This is helpful to visualize objects dynamically using Studio Live.

class CylinderΒΆ

A cylinder collision object.

float radiusΒΆ

Radius of the cylinder.

float lengthΒΆ

Length of the cylinder.

Cylinder(float radius, float length)ΒΆ

Construct a cylinder with the given radius and length.

class HeightFieldΒΆ

A height field or depth map collision object.

using Matrix = std::vector<std::vector<double>>ΒΆ
float xΒΆ

Size along the x-axis.

float yΒΆ

Size along the y-axis.

Matrix heightsΒΆ

Matrix containing the heights at evenly spaced grid points. The collision object will interpolate linearly between the heights, and will create a volume to zero height.

HeightField(float x, float y, const Matrix &heights)ΒΆ

Construct a height field with the given data.

class SphereΒΆ

A sphere collision object.

float radiusΒΆ

Radius of the sphere.

Sphere(float radius)ΒΆ

Construct a sphere with the given radius.

class Obstacle : ElementΒΆ

An environment obstacle.

using Object = std::variant<Box, Capsule, Convex, Cylinder, HeightField, Sphere>ΒΆ
std::string nameΒΆ

The name of the obstacle.

std::string colorΒΆ

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

Object collisionΒΆ

The object for collision checking.

Frame originΒΆ

The pose of the object.

bool for_visual = trueΒΆ

Whether this obstacle is used for visual checking.

bool for_collision = trueΒΆ

Whether this obstacle is used for collision checking.

float safety_margin = 0.0ΒΆ

An additional obstacle-specific safety margin. Currently, only positive values are supported. Setting a value of -infinity disables the collision check completely.

Obstacle(const Box &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const Capsule &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const Convex &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const Cylinder &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const Sphere &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const std::string &name, const Box &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const std::string &name, const Capsule &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const std::string &name, const Convex &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const std::string &name, const Cylinder &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ
Obstacle(const std::string &name, const Sphere &object, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ

EnvironmentΒΆ

class EnvironmentΒΆ
double safety_marginΒΆ

Additional global safety margin used for collision checking.

Environment(std::shared_ptr<Robot> robot, float safety_margin = 0.0)ΒΆ
std::shared_ptr<Robot> get_robot(const std::string &name = "")ΒΆ

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.

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

Get the waypoint with the given name from the environment. Returns either a Waypoint, a CartesianWaypoint, a Region, or a CartesianRegion. Throws an error if no waypoint with the name exists.

Point get_waypoint_by_tag(const std::string &tag)ΒΆ

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

Obstacle get_obstacle(const std::string &name)ΒΆ

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

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

Get all obstacles within the environment that carry the given tag. Tags are case-insensitive.

Obstacle *add_obstacle(const Obstacle&)ΒΆ

Adds an obstacle to the environment. Returns a pointer to the added obstacle for future changes.

Obstacle *add_obstacle(const Object&, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

Obstacle *add_obstacle(const std::string &name, const Object&, const Frame &origin = Frame::Identity(), const std::string &color = "000000")ΒΆ

Adds a collision object to the environment at the given origin frame. Returns a pointer to the added obstacle for future changes.

void remove_obstacle(Obstacle *obstacle)ΒΆ

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

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_height_field(Obstacle *obstacle)ΒΆ

Updates the heights matrix of a given height field obstacle for the internal collision checking.

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.

bool check_collision(const Config &joint_position)ΒΆ

Returns true if the given joint position is in collision with the environment, otherwise false.

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

Returns true if the given joint position for the specific robot is in collision with the environment, otherwise false.

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.

RobotsΒΆ

class RobotΒΆ
std::string modelΒΆ

The model name of the robot.

std::string nameΒΆ

The unique name of the robot in the project.

void set_base(const Frame &base)ΒΆ

Sets the origin of the robot’s base.

Frame base() constΒΆ

Get the origin of the robot’s base.

void set_speed(double speed)ΒΆ

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

static Robot from_model(const std::string &model)ΒΆ

Returns the robot with the given model name.

class RobotArm : RobotΒΆ
const size_t degrees_of_freedomΒΆ

The number of joints of the robot.

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]

The obstacles for each robot link.

std::optional<Obstacle> end_effector_obstacleΒΆ

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

std::optional<Obstacle> item_obstacleΒΆ

An (optional) obstacle attached to the robot’s TCP. The obstacle’s frame is defined relative to the TCP frame.

void set_flange_to_tcp(const Frame &flange_to_tcp)ΒΆ

The transformation from the robot’s flange to the robot’s TCP, e.g. for using inverse kinematics or an item obstacle.

Frame flange_to_tcp() constΒΆ
void set_speed(double speed)ΒΆ

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

void forward_position(const Config &joint_position)ΒΆ

Calculates the link and joint frames along the kinematic chain for the given joint position.

Frame calculate_tcp(const Config &joint_position)ΒΆ

Calculates the forward_kinematics and 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.

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

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.


class ABBIRB1200590 : RobotArmΒΆ

Defined in the <jacobi/robots/abb_irb1200_5_90.hpp> header.

class ABBIRB1300714 : RobotArmΒΆ

Defined in the <jacobi/robots/abb_irb1300_7_14.hpp> header.

class ABBIRB1600612 : RobotArmΒΆ

Defined in the <jacobi/robots/abb_irb1600_6_12.hpp> header.

class ABBIRB460060205 : RobotArmΒΆ

Defined in the <jacobi/robots/abb_irb4600_60_205.hpp> header.

class ABBIRB6700150320 : RobotArmΒΆ

Defined in the <jacobi/robots/abb_irb6700_150_320.hpp> header.

class ABBYuMiIRB14000 : RobotΒΆ

Defined in the <jacobi/robots/abb_yumi_irb14000.hpp> header.

ABBYuMiArm leftΒΆ
ABBYuMiArm rightΒΆ
class DualArm : RobotΒΆ

Defined in the <jacobi/robots/dual_arm.hpp> header.

std::shared_ptr<RobotArm> leftΒΆ
std::shared_ptr<RobotArm> rightΒΆ
DualArm(std::shared_ptr<RobotArm> left, std::shared_ptr<RobotArm> right)ΒΆ
class FanucLR10iA10 : RobotArmΒΆ

Defined in the <jacobi/robots/fanuc_lr_10ia10.hpp> header.

class FanucLRMate200iD7L : RobotArmΒΆ

Defined in the <jacobi/robots/fanuc_lrmate200id7l.hpp> header.

class FanucM20iB25 : RobotArmΒΆ

Defined in the <jacobi/robots/fanuc_m_20ib25.hpp> header.

class FanucM710iC45M : RobotArmΒΆ

Defined in the <jacobi/robots/fanuc_m_710ic45m.hpp> header.

class FrankaPanda : RobotArmΒΆ

Defined in the <jacobi/robots/franka_panda.hpp> header.

class KinovaGen37DoF : RobotArmΒΆ

Defined in the <jacobi/robots/kinova_gen3_7dof.hpp> header.

class KukaIiwa7 : RobotArmΒΆ

Defined in the <jacobi/robots/kuka_iiwa7.hpp> header.

class MecademicMeca500 : RobotArmΒΆ

Defined in the <jacobi/robots/mecademic_meca500.hpp> header.

class UfactoryXArm7 : RobotArmΒΆ

Defined in the <jacobi/robots/ufactory_xarm7.hpp> header.

class UniversalUR5e : RobotArmΒΆ

Defined in the <jacobi/robots/universal_ur5e.hpp> header.

class UniversalUR10 : RobotArmΒΆ

Defined in the <jacobi/robots/universal_ur10.hpp> header.

class UniversalUR10e : RobotArmΒΆ

Defined in the <jacobi/robots/universal_ur10e.hpp> header.

class UniversalUR20 : RobotArmΒΆ

Defined in the <jacobi/robots/universal_ur20.hpp> header.

class YaskawaGP12 : RobotArmΒΆ

Defined in the <jacobi/robots/yaskawa_gp12.hpp> header.

class YaskawaHC10 : RobotArmΒΆ

Defined in the <jacobi/robots/yaskawa_hc10.hpp> header.

class YaskawaHC20 : RobotArmΒΆ

Defined in the <jacobi/robots/yaskawa_hc20.hpp> header.

class CustomRobot : RobotΒΆ

Defined in the <jacobi/robots/custom.hpp> header.

Warning

Custom robots are in a beta preview with rudimentary support right now. If possible, prefer to use robots from our supported robot library, as they will be significantly faster to compute and easier to use.

The translations between the links.

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

The axis of the joints.

std::vector<JointType> joint_typesΒΆ

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

static CustomRobot load_from_urdf_file(const std::filesystem::path &file, const std::string &base_link = "base_link", const std::string &end_link = "flange")ΒΆ

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.

MotionsΒΆ

class LinearSectionΒΆ

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

Frame offsetΒΆ

Relative linear cartesian offset from either the start of the goal.

double speed = 1.0ΒΆ

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

LinearSection::Approximation approximation = LinearSection.Approximation.AlwaysΒΆ

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

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.

std::string nameΒΆ

The unique name of the motion.

Point startΒΆ

Start point of the motion.

Point goalΒΆ

Goal point of the motion.

std::vector<Point> 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::shared_ptr<Robot> robotΒΆ

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

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.

double orientation_target = {0.0, 0.0, 1.0}ΒΆ

Target vector pointing in the direction of the end-effector (TCP) orientation in the world 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)

Motion(const std::string &name, std::shared_ptr<Robot> robot, const Point &start, const Point &goal)ΒΆ
class LinearMotionΒΆ

Represents a request for a linear Cartesian-space motion.

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).

LinearMotion(const std::string &name, std::shared_ptr<Robot> robot, const ExactPoint &start, const ExactPoint &goal)ΒΆ
class LowLevelMotionΒΆ

Represents a request for a low-level motion. 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.

enum ControlInterfaceΒΆ
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ΒΆ
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ΒΆ
enumerator ContinuousΒΆ

Every trajectory synchronization duration is allowed. (Default)

enumerator DiscreteΒΆ

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

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 point of the motion.

Waypoint goalΒΆ

Goal point 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.

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

Motion PlanningΒΆ

class TrajectoryΒΆ
std::string idΒΆ

Field for identifying trajectories (for the user).

std::string motionΒΆ

Name of the motion this trajectory was planned for.

double durationΒΆ

The trajectory 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.

Trajectory reverse() constΒΆ

Reverse the trajectory’s start and goal.

void append(const Trajectory &other)ΒΆ

Appends another trajectory to the current one.

Trajectory slice(size_t start, size_t steps) constΒΆ

Get a slice of the trajectory starting from step start for a length of steps.

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

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.

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

Loads a trajectory from a *.json file.

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

Saves a trajectory to a *.json file.

size_t size()ΒΆ

The number of time steps within the trajectory.

std::string as_table() constΒΆ

To pretty print the trajectory as a table of positions.

class PlannerΒΆ
double delta_timeΒΆ

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

double last_calculation_durationΒΆ

The duration of the last motion planning calculation in [ms].

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

Constructs a planner for the given environment.

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

Constructs a planner for the given robot and an empty environment.

Planner(const std::string &project, double delta_time)ΒΆ

Cloud version: Constructs a planner with the environment defined in the given Jacobi Studio project.

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

Loads a planner from the Studio project with the given name. It will download and update the project automatically. Requires the JACOBI_API_KEY environment variable to be set.

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

Loads a planner from a *.jacobi-project file.

void add_motion(const Motion<Robot> &motion)ΒΆ
void add_motions(const std::vector<Motion<Robot>> &motions)ΒΆ
void load_motion_plan(const std::filesystem::path &file)ΒΆ

On-prem version: Loads a motion plan from the *.jacobi-plan file.

std::optional<Trajectory> plan(const ExactPoint &start, const ExactPoint &goal)ΒΆ

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

std::optional<Trajectory> plan(const std::string &motion_name, const std::optional<ExactPoint> &start, const std::optional<ExactPoint> &goal)ΒΆ

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.

std::optional<Trajectory> plan(const Motion &motion)ΒΆ

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

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

Plans a linear motion.

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

Plans a low-level motion.

Studio LiveΒΆ

class StudioΒΆ

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

class ActionΒΆ

An action that can be performed in Jacobi Studio, e.g. setting a robot to a specific joint position or adding an obstacle to the environment.

class 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).

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

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

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

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

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

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

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

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

static Action add_obstacle(const Obstacle &obstacle) constΒΆ

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

static Action add_waypoint(const Point &point) constΒΆ

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

static Action remove_obstacle(const Obstacle &obstacle) constΒΆ

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

static 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.

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

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

Studio()ΒΆ

Connects to Jacobi Studio automatically. Please make sure to enable the Studio Live feature in the Jacobi Studio settings.

double speedup = 1.0ΒΆ

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

void 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.

void 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.

void 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.

void add_robot(const std::shared_ptr<Robot> &robot) constΒΆ

Adds the given robot to the environment.

void add_obstacle(const Obstacle &obstacle) constΒΆ

Adds the given obstacle to the environment.

void add_waypoint(const Point &point) constΒΆ

Adds the given point to the environment.

void remove_obstacle(const Obstacle &obstacle) constΒΆ

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

void 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.

void set_camera_depth_map(const std::vector<std::vector<double>> depths, double x, double y, const std::shared_ptr<Camera> camera = nullptr) constΒΆ

Sets the depth map visualization of a camera.

void run_action(const Action &action) constΒΆ

Run the given action in Jacobi Studio.

void 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.

void run_events(const Events &events) constΒΆ

Run the events at the specified timings in Jacobi Studio.

void 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.

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

Return the current joint position of the given or only robot.

Robot DriverΒΆ

enum ResultΒΆ
enumerator Success = 1ΒΆ

Finished successfully.

enumerator Error = -1ΒΆ

General (unspecified) error.

enumerator ErrorStartPositionDeviation = -100ΒΆ

The start position of the trajectory deviates from the current robot’s position.

enumerator ErrorTrajectoryDidNotUpdate = -101ΒΆ

Failed to update the trajectory.

enumerator ErrorReachGoalTimeout = -102ΒΆ

Waiting to reach goal position has timed out.

enumerator ErrorCommandAlreadyInProgress = -103ΒΆ

Another command already in progress.

enumerator ErrorTrajectoryAborted = -104ΒΆ

Trajectory aborted by stop command.

enumerator ErrorController = -200ΒΆ

General error on the controller.

enumerator ErrorControllerEStopActive = -201ΒΆ

E-Stop is active on the controller.

enumerator ErrorControllerSafetyViolation = -202ΒΆ

Safety violation occured on the controller.

enumerator ErrorControllerAlarmActive = -203ΒΆ

An alarm is active on the controller.

enumerator ErrorControllerNotInAutoMode = -204ΒΆ

Controller is not in automatic mode.

enumerator ErrorControllerNotInRemoteMode = -205ΒΆ

Controller not in a remote mode for external control.

enumerator ErrorControllerInHoldState = -206ΒΆ

Controller is in a hold state.

enumerator ErrorControllerEnableMotors = -207ΒΆ

The robot’s motors are not enabled.

enumerator ErrorControllerProgramStopped = -208ΒΆ

Controller program stopped unexpectedly.

enumerator ErrorControllerSendingStop = -209ΒΆ

Failed to send the stop command to the controller.

enumerator ErrorControllerConnection = -210ΒΆ

No connection to controller.

class FutureResultΒΆ
Result wait()ΒΆ

Blocks the code execution until the robot has finished the motion and then returns its result.

bool has_finished()ΒΆ

Returns whether the corresponding motions has already finished.

class DriverΒΆ
bool reconnect()ΒΆ

Connect to the robot, in particular after an external disconnection. Returns reconnection success.

bool disconnect()ΒΆ

Disconnect from the robot. Returns disconnection success.

bool is_connected() constΒΆ

Is the robot currently connected?

ControllerStatus get_controller_status() constΒΆ

Current status of the robot’s controller.

Result enable()ΒΆ

Enable robot’s servos (if available).

Result disable()ΒΆ

Disable robot’s servos (if available).

bool is_running() constΒΆ

Is the robot is currently running a motion in a synchronously or asynchronously manner?

double get_speed() constΒΆ

The speed parameter to change the driver’s execution speed. It is usually between 0.0 and 1.0, or might be higher for the SimulatedDriver for faster than real-time speeds.

void set_speed(double speed)ΒΆ

Sets the speed parameter.

void set_speed(double speed, double duration)ΒΆ

Change the speed parameter smoothly with a linear interpolation over the given time duration [s].

Config get_current_joint_position() constΒΆ

Returns the current joint position of the robot.

RobotState get_current_state() constΒΆ

Returns the current joint state of the robot. Velocity and acceleration information are only available for some drivers.

Result run(const Trajectory &trajectory)ΒΆ

Run a trajectory.

FutureResult run_async(const Trajectory &trajectory)ΒΆ

Run a trajectory asynchronously.

Result move_to(const ExactPoint &goal, bool ignore_collision = false)ΒΆ

Move to an exact waypoint.

FutureResult move_to_async(const ExactPoint &goal, bool ignore_collision = false)ΒΆ

Move to an exact waypoint asynchronously.

Result move_along(const std::string &name, bool ignore_collision = false)ΒΆ

Move along a pre-defined motion profile.

FutureResult move_along_async(const std::string &name, bool ignore_collision = false)ΒΆ

Move along a pre-defined motion profile asynchronously.

Result blend_into(const Trajectory &trajectory, double duration)ΒΆ

Blend into the new trajectory from the current state, so that the robot will be on the given trajectory exactly after the duration time [s].

FutureResult blend_into_async(const Trajectory &trajectory, double duration)ΒΆ

Blend into the new trajectory from the current state, so that the robot will be on the given trajectory exactly after the duration time [s].

Result stop(bool fast_stop = true)ΒΆ

Stop a motion as fast as possible.

FutureResult stop_async(bool fast_stop = true)ΒΆ

Stop a motion as fast as possible asynchronously.

void create_io_alias(const std::string &name, size_t address)ΒΆ

Creates an alias name for a given I/O address.

int get_digital_input(const std::string &name)ΒΆ

Read a digital input.

bool set_digital_output(const std::string &name, int value)ΒΆ

Write to a digital output. Returns whether successful.

float get_analog_input(const std::string &name)ΒΆ

Read a analog input.

bool set_analog_output(const std::string &name, float value)ΒΆ

Write to a analog output. Returns whether successful.

int get_group_input(const std::string &name)ΒΆ

Read a group input.

bool set_group_output(const std::string &name, int value)ΒΆ

Write to a group output. Returns whether successful.


class ABBDriver : DriverΒΆ
class RapidModuleΒΆ
RapidModule(const std::string &unit = "ROB_1", const std::string &egm_config = "default", double max_speed_deviation = 100.0)ΒΆ

Create a new Rapid module.

RapidModule(const std::string &manual_code)ΒΆ

Create a module with completly custom manual Rapid code.

std::string unitΒΆ

The name of the robot unit to be controlled.

bool upload = trueΒΆ

Whether the rapid file should be uploaded to the controller on connection.

void add_procedure(const std::string &name, const std::string &rapid)ΒΆ

Adds a procedure to call with arbitrary Rapid code.

std::string get_rapid_code(const std::string &init = "egm")ΒΆ

Returns the overall Rapid code.

class RWSΒΆ

A robot connection using the ABB Robot Web Services interface.

class SignalΒΆ
std::string nameΒΆ

The name of the signal.

std::string categoryΒΆ

The category of the signal.

std::string lvalueΒΆ

The current value of the signal.

std::string get_version()ΒΆ

Get the version of the robot controller.

std::string get_robot_type()ΒΆ

Get the robot type.

int get_speed_ratio()ΒΆ

Get the robot’s speed ratio.

void set_speed_ratio(int speed_ratio)ΒΆ

Set the robot’s speed ratio.

Config get_joint_position(const std::string &mechunit = "ROB_1")ΒΆ

Get the current robot unit joint position via the RWS interface.

void call_procedure(const std::string &name)ΒΆ

Call a Rapid procedure.

Result execute_rapid_main()ΒΆ

Execute the current Rapid program from main.

Result execute(const RapidModule &module, const std::string &init = "egm")ΒΆ

Executes the given Rapid module, starting from the given method.

void stop_execution()ΒΆ

Stop the execution of the currently running program.

void restart_controller()ΒΆ

Restart the controller.

Signal get_signal(const std::string &signal, const std::string &network = "", const std::string &device = "")ΒΆ

Read the signal of the given name.

void set_signal(const std::string &signal, const std::string &value, const std::string &network = "", const std::string &device = "")ΒΆ

Write the signal to the given value.

std::shared_ptr<RWS> rwsΒΆ

The RWS module, if initialized.

ABBDriver(std::shared_ptr<Planner> planner, int port)ΒΆ

Starts an ABB Robot Driver using an underlying EGM server at the specified port.

ABBDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, int port)ΒΆ

Starts an ABB Robot Driver for a specified robot using an underlying EGM server at the specified port.

ABBDriver(std::shared_ptr<Planner> planner, const std::string &host, const RapidModule &module = RapidModule(), RobotWareVersion version = RobotWareVersion.RobotWare7)ΒΆ

Starts an ABB Robot Driver with an underyling RWS connection.

ABBDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, const std::string &host, const RapidModule &module = RapidModule(), RobotWareVersion version = RobotWareVersion.RobotWare7)ΒΆ

Starts an ABB Robot Driver for a specified robot with an underyling RWS connection.

ABBDriver(std::shared_ptr<Planner> planner, const std::string &host, int port, const RapidModule &module = RapidModule(), RobotWareVersion version = RobotWareVersion.RobotWare7)ΒΆ

Starts an ABB Robot Driver with both an EGM server and an RWS connection.

ABBDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, const std::string &host, int port, const RapidModule &module = RapidModule(), RobotWareVersion version = RobotWareVersion.RobotWare7)ΒΆ

Starts an ABB Robot Driver for a specified robot with both an EGM server and an RWS connection.

class SimulatedDriver : DriverΒΆ
double time_speed = 1.0ΒΆ

A factor for speeding up the time, e.g. for faster than real-world simulations.

Studio studioΒΆ

The underlying connection to Jacobi Studio.

Result run_result = Result::SuccessΒΆ

The result type for motions.

Result enable_result = Result::SuccessΒΆ

The result type for enabling or disabling the controller.

bool connect_result = trueΒΆ

The result type for reconnecting or disconnection the controller.

SimulatedDriver(std::shared_ptr<Planner> planner, bool sync_with_studio = false, bool log_stream = false, bool serve_io_viewer = false)ΒΆ

Starts an Simulated Robot Driver, possibly connecting to Jacobi Studio via Studio Live, or streaming the current positions to cout.

SimulatedDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, bool sync_with_studio = false, bool log_stream = false, bool serve_io_viewer = false)ΒΆ

Starts an Simulated Robot Driver, possibly connecting to Jacobi Studio via Studio Live, or streaming the current positions to cout. Controls the given robot only.

void set_current_joint_position(const Config &joint_position)ΒΆ

Sets the current robot’s joint position to the given value.

void create_io(const std::string &name, std::variant<int, float> default_value)ΒΆ

Create a simulated I/O with the given name and default value.

void load_io_config(const std::vector<Signal> &config)ΒΆ

Load a config a list of signals to create multiple I/Os at once.

void load_io_config_from_file(const std::filesystem::path &file)ΒΆ

Load a config from file to create multiple I/Os at once. The file required to be a *.json with names mapping to their default values.

class UniversalDriver : DriverΒΆ
UniversalDriver(std::shared_ptr<Planner> planner, const std::string &host)ΒΆ

Starts an Universal Robot Driver using RTDE.

UniversalDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, const std::string &host)ΒΆ

Starts an Universal Robot Driver using RTDE. Controls the given robot only.

class YaskawaDriver : DriverΒΆ
YaskawaDriver(std::shared_ptr<Planner> planner, const std::string &host = "192.168.1.31", int port = 50240)ΒΆ

Starts an Yaskawa Robot Driver connecting to the MotoPlus application running on the robot controller.

YaskawaDriver(std::shared_ptr<Planner> planner, std::shared_ptr<Robot> robot, const std::string &host = "192.168.1.31", int port = 50240)ΒΆ

Starts an Yaskawa Robot Driver connecting to the MotoPlus application running on the robot controller. Controls the given robot only.