RDK Library

All functionalities of Flexiv RDK are packed into a library, which allows the robot to be monitored and controlled by a workstation PC running programs linked to the library. The robot can be put into different modes to execute different types of commands: real-time modes allow the robot to take and execute low-level motion control commands at 1kHz, while non-real-time modes are for high-level operation instructions or discrete motion commands.

Overview

Below is an overview of the RDK library:

flexiv_rdk
├── cmake
│   └── (CMake modules and configuration file)
├── example
│   └── (C++ examples)
├── example_py
│   └── (Python examples)
├── include
│   └── (headers describing the APIs)
├── lib
│   └── (C++ libraries for various OS and CPU platforms)
├── lib_py
│   └── (Python libraries for various OS and CPU platforms)
├── resources
│   └── (URDF with accurate robot kinematics but approximated dynamics)
│   └── meshes
│       └── (mesh files for visual and collision)
├── test
│   └── (functionality tests)
└── thirdparty
    └── eigen3 (header-only Eigen library required by RDK)

API documentation

Detailed API documentation of Flexiv RDK can be found at https://rdk.flexiv.com/api/.

API access

RDK currently supports multiple [OS - language] interfaces. The Linux C++ and macOS C++ interface have full access to all APIs, while the other interfaces have partial access as shown below:

API

Windows C++

All Python interfaces

flexiv::Robot

Full access

Partial access (exclusion: methods marked as “Real-time”)

flexiv::Gripper

Full access

Full access

flexiv::Log

Full access

Full access

flexiv::Mode

Full access

Partial access (exclusion: real-time modes)

flexiv::Exception

Full access

No access (function exception is still active and can be caught as Exception)

flexiv::Model

No access

No access

flexiv::Scheduler

No access

No access

Data.hpp

Full access

Partial access (exclusion: operator overloading functions)

Robot description (URDF)

The URDF files of all Flexiv Rizon models can be found under flexiv_rdk/resources directory. The visual and collision mesh files are also available under this directory.

Note

The URDF files contain accurate robot kinematics parameters but blurred robot dynamics parameters. Accurate dynamics data can be accessed via the flexiv::Model API.

Robot control modes

The robot can be put into different control modes to execute different kinds of commands. Most command-execution methods require the user to put the robot into a corresponding control mode using flexiv::Robot::setMode() before sending the actual command. This is to get the robot prepared for the incoming commands. A list of all robot control modes is shown below, which are also available in Mode.hpp.

Idle mode

The robot decelerates to a complete stop and holds its current position while waiting for new user command. The corresponding enum of this mode is flexiv::Mode::IDLE.

Real-time (RT) control modes

When the robot is in real-time control modes, the user can stream real-time commands at 1kHz, which will be executed immediately without any excessive processing to ensure the control loop is running at 1kHz.

RT joint torque control mode

The robot accepts joint torque commands streamed at 1kHz, and execute immediately them using a built-in joint torque controller. Gravity, friction, and other nonlinear dynamics are compensated. The corresponding enum of this mode is flexiv::Mode::RT_JOINT_TORQUE, and the command can be sent to the robot via flexiv::Robot::streamJointTorque(). Please refer to the function doc for more details.

RT joint position control mode

The robot accepts joint position commands streamed at 1kHz, and execute them immediately using a built-in joint position controller. Gravity, friction, and other nonlinear dynamics are compensated. The corresponding enum of this mode is flexiv::Mode::RT_JOINT_POSITION, and the command can be sent to the robot via flexiv::Robot::streamJointPosition(). Please refer to the function doc for more details.

RT Cartesian motion-force control mode

The robot accepts Cartesian motion and/or force commands streamed at 1kHz, and execute them immediately using a built-in unified motion-force controller. Gravity, friction, and other nonlinear dynamics are compensated. The corresponding enum of this mode is flexiv::Mode::RT_CARTESIAN_MOTION_FORCE, and the command can be sent to the robot via flexiv::Robot::streamCartesianMotionForce(). Please refer to the function doc for more details.

Non-real-time control modes

When the robot is in non-real-time control modes, the user can send one-shot or slow-periodic control commands and high-level operation instructions like plans and primitives.

NRT joint position control mode

The robot accepts joint position commands in one-shot or slow-periodic manner. A built-in motion generator will produce smooth joint-space trajectories based on the discrete commands, then the trajectory will be executed using a built-in joint position controller. Gravity, friction, and other nonlinear dynamics are compensated. The corresponding enum of this mode is flexiv::Mode::NRT_JOINT_POSITION, and the command can be sent to the robot via flexiv::Robot::sendJointPosition(). Please refer to the function doc for more details.

NRT Cartesian motion-force control mode

The robot accepts Cartesian motion and/or force commands in one-shot or slow-periodic manner. A built-in motion generator will produce smooth Cartesian-space trajectories based on the discrete commands, then the trajectory will be executed using a built-in Cartesian unified motion-force controller. Gravity, friction, and other nonlinear dynamics are compensated. The corresponding enum of this mode is flexiv::Mode::NRT_CARTESIAN_MOTION_FORCE, and the command can be sent to the robot via flexiv::Robot::sendCartesianMotionForce(). Please refer to the function doc for more details.

Primitive execution mode

The robot accepts and executes primitives specified by the user. The corresponding enum of this mode is flexiv::Mode::NRT_PRIMITIVE_EXECUTION. The primitive command and parameters can be sent to the robot via flexiv::Robot::executePrimitive(). Please refer to the function doc for more details.

Plan execution mode

The robot accepts and executes plans specified by the user. The corresponding enum of this mode is flexiv::Mode::NRT_PLAN_EXECUTION. A list of available plans can be obtained via flexiv::Robot::getPlanNameList(), and the plan command can be sent to the robot via flexiv::Robot::executePlan(). Please refer to the function doc for more details.

Robot states

Robot states refer to the measured and estimated information of the robot. The data structure containing these information is flexiv::RobotStates in header file Data.hpp. Robot states are updated and published to the user in real time at 1kHz. However, the user can control how frequently they fetch the data by simply controlling the rate at which flexiv::Robot::getRobotStates() is called.

Digital I/O control

Flexiv RDK can also control the digital I/O ports located on the robot’s control box. A total of 16 digital outputs and 16 digital inputs are available. The digital inputs can be read via flexiv::Robot::readDigitalInput(), and the digital outputs can be written via flexiv::Robot::writeDigitalOutput().