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.

Waypoints#

class Waypoint#

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#

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#

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#

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 Point = std::variant<Config, Waypoint, CartesianWaypoint, Region, CartesianRegion>#

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

using ExactPoint = std::variant<Config, Waypoint, CartesianWaypoint, Region, CartesianRegion>#

All types for speciying 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 xyaxis.

Matrix heights#

Matrix containing the heights at evenly spaced grid points.

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#

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.

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.

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.

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)#
void set_speed(double speed)#
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.

Frame &base()#
Frame base() 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. 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 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.

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

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_project_file(const std::filesystem::path &file)#

On-prem version: 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.

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

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

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

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, int default_value)#

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

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

Starts an Universal Robot Driver using RTDE.

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.