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)
-
std::string model
-
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]
-
std::vector<Obstacle> link_obstacles
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.
-
const size_t degrees_of_freedom
-
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
-
ABBYuMiArm left
-
class DualArm : Robot
Defined in the
<jacobi/robots/dual_arm.hpp>
header.-
std::shared_ptr<RobotArm> left
-
std::shared_ptr<RobotArm> right
-
std::shared_ptr<RobotArm> left
-
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.-
std::vector<Frame> link_translations
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 givenbase_link
and theend_link
.
-
std::vector<Frame> link_translations