Skip to main content

SDK Introduction

Overview

The xCore SDK programming interface library is a software product provided by Rokae Robotics for customers to perform secondary development. Through the programming interface library, customers can perform a series of controls and operations on robots equipped with the xCore system, including real-time and non-real-time motion control, robot communication-related read/write operations, querying and running RL projects, etc. This user manual mainly introduces the usage of the programming interface library and the functions of each interface function. Users can write their own applications and integrate them into external software and hardware modules.

Compatibility

Controller Version and Robot Models

  • Controller version: xCore v3.0.1 and later.

  • Robot models: Supports control of all models. Depending on the different functions supported by collaborative and industrial robots, the callable interfaces vary.

Compilation Platform and Language

Operating SystemCompilerPlatformLanguage
Ubuntu 18.04/20.04/22.04build-essentialx86_64 aarch64C++,Python
Windows 10MSVC 14.1+x86_64C++,Python,C#
Androidarmeabi-v7a,arm64-v8a,x86,x86_64Java

Non-Real-Time Control

The xCore SDK provides non-real-time control of the robot, mainly by sending motion commands to the robot and using the controller's internal trajectory planning to complete path planning and motion execution. Operations provided in non-real-time mode include:

  • Motion: Joint space motion (MoveAbsJ,MoveJ), Cartesian space motion (MoveL,MoveC,MoveCF,MoveSP), support for rail linkage. And reachability verification, setting acceleration, etc.
  • Force control commands
  • Robot communication: Digital and analog I/O, register read/write, XMS and XMC models end 485 communication
  • Query and execution of RL projects
  • Dragging and path playback (only for xMate collaborative robots)
  • Other operations: Jog, setting collision detection, soft limits, clearing alarms, querying controller logs, etc.

Real-Time Control

1. Overview

The real-time control of the xCore SDK includes a series of low-level control interfaces. Research or secondary development users can use this software package to achieve real-time control up to 1KHz for algorithm verification and new application development.

  • xMate collaborative robots support 5 control modes:
    • Joint space position control
    • Cartesian space position control
    • Joint space impedance control
    • Cartesian space impedance control
    • Direct torque control
  • 6-axis industrial robots support 2 position control modes:
    • Joint space position control
    • Cartesian space position control
  • Industrial 3, 4-axis models are temporarily not supported.

2. Minimum System and Network Requirements

This page only specifies the requirements for running the Rokae Control Interface (RCI). Other requirements are specified in the received robot documentation.

2.1 Workstation PC

Minimum System Requirements
Operating SystemLinux real-time kernel,
Network CardRealtek network card, Intel network cards are not recommended

Since the robot sends data at a frequency of 1kHz, it is important to configure the workstation PC for the lowest possible latency. For example, it is recommended to disable CPU frequency scaling. Other possible optimizations will depend on the specific system.

2.2 Disabling CPU Frequency Scaling

CPUs are usually configured to use lower operating frequencies under light loads to save power. We recommend disabling this feature as it can cause high latency when using Rokae. To check and modify the power-saving mode, install the cpufrequtils package:

sudo apt install cpufrequtils

Run cpufreq-info to view available "governors" and current CPU frequency. Below is a sample output:

$ cpufreq-info
...
analyzing CPU 0:
driver: intel_pstate
CPUs which run at the same hardware frequency: 0
CPUs which need to have their frequency coordinated by software: 0
maximum transition latency: 0.97 ms.
hardware limits: 400 MHz - 3.00 GHz
available cpufreq governors: performance, powersave
current policy: frequency should be within 400 MHz and 3.00 GHz.
The governor "powersave" may decide which speed to use
within this range.
current CPU frequency is 500 MHz.

In this example, the maximum frequency is 3 GHz, but the current frequency is 500 Mhz due to the power-saving policy. In this case, we can benefit by setting the governor to performance mode.

To change this setting using the Ubuntu GUI, install the indicator-cpufreq package. The widget in the top bar of the Unity user interface (i.e., at the top of the screen) should allow setting the current policy.

To change this setting using the terminal, execute the following commands:

sudo systemctl disable ondemand
sudo systemctl enable cpufrequtils
sudo sh -c 'echo "GOVERNOR=performance" > /etc/default/cpufrequtils'
sudo systemctl daemon-reload && sudo systemctl restart cpufrequtils

This will disable the ondemand CPU scaling daemon, create a /etc/default/cpufrequtils configuration file, and then restart the cpufrequtils service.

After enabling the performance governor, the cpufreq-info result is:

$ cpufreq-info
...
analyzing CPU 0:
driver: intel_pstate
CPUs which run at the same hardware frequency: 0
CPUs which need to have their frequency coordinated by software: 0
maximum transition latency: 0.97 ms.
hardware limits: 400 MHz - 3.00 GHz
available cpufreq governors: performance, powersave
current policy: frequency should be within 400 MHz and 3.00 GHz.
The governor "performance" may decide which speed to use
within this range.
current CPU frequency is 2.83 GHz.

Now the example output shows the CPU frequency is close to the maximum frequency. You can also use the cpufreq-info -p command to directly verify the current governor.

2.3 Network

If possible, please connect the workstation PC directly to the controller's Control LAN port, i.e., avoid any intermediate devices such as switches. Intermediate relays may cause latency, jitter, or packet loss. This will degrade controller performance or make it unusable.

To control the robot, the sum of the following time measurements must be less than 1ms:

  • Round trip time (RTT) between workstation PC and RCI
  • Execution time of the motion generator or control loop
  • Time required for the robot to process data and step the internal controller

3. Best Practices for Real-Time Control Loops

When implementing a 1 kHz control loop with Rokae, it is essential to ensure that the code can execute within the 1ms time limit. That is, all operations from reading to writing commands must be completed within 1ms.

The time limit may become uncontrollable in the following situations:

  • Using a switch to connect the control computer
  • Insufficient network card performance
  • Not using a real-time kernel

3.1 What Not to Do in a 1 kHz Control Loop

❌ Do NOT: Load files or models in the loop

  std::function<CartesianPosition()> callback = [&, rtCon]()
{
time += 0.001;
double delta_angle = M_PI / 20.0 * (1 - std::cos(M_PI / 2.5 * time));
JointPosition cmd = {{jntPos[0] + delta_angle, jntPos[1] + delta_angle, jntPos[2] - delta_angle,
jntPos[3] + delta_angle, jntPos[4] - delta_angle, jntPos[5] + delta_angle,
jntPos[6] - delta_angle}};
if (time > 60)
{
cmd.setFinished(); // End after 60 seconds
}
//Do NOT use
traceOfsLoop_.open(("get" +
std::to_string(std::chrono::duration_cast<std::chrono::milliseconds>(
std::chrono::system_clock::now().time_since_epoch())
.count()) +
".txt"),
std::ios::out);
return cmd
};

❌ Do NOT: Use sleep or blocking operations

 std::function<CartesianPosition()> callback = [&, rtCon]()
{
time += 0.001;
double delta_angle = M_PI / 20.0 * (1 - std::cos(M_PI / 2.5 * time));
JointPosition cmd = {{jntPos[0] + delta_angle, jntPos[1] + delta_angle, jntPos[2] - delta_angle,
jntPos[3] + delta_angle, jntPos[4] - delta_angle, jntPos[5] + delta_angle,
jntPos[6] - delta_angle}};
if (time > 60)
{
cmd.setFinished(); // End after 60 seconds
}
//Do NOT use
std::this_thread::sleep_for(std::chrono::milliseconds(1));
return cmd;

};

❌ Do NOT: Print output in each loop

 std::function<CartesianPosition()> callback = [&, rtCon]()
{
time += 0.001;
double delta_angle = M_PI / 20.0 * (1 - std::cos(M_PI / 2.5 * time));
JointPosition cmd = {{jntPos[0] + delta_angle, jntPos[1] + delta_angle, jntPos[2] - delta_angle,
jntPos[3] + delta_angle, jntPos[4] - delta_angle, jntPos[5] + delta_angle,
jntPos[6] - delta_angle}};
if (time > 60)
{
cmd.setFinished(); // End after 60 seconds
}
//Do NOT use
print(std::cout, "jntPos:", jntPos);
return cmd
};

❌ Do NOT: Perform dynamic memory allocation in the loop

 std::function<CartesianPosition()> callback = [&, rtCon]()
{
time += 0.001;
double delta_angle = M_PI / 20.0 * (1 - std::cos(M_PI / 2.5 * time));
JointPosition cmd = {{jntPos[0] + delta_angle, jntPos[1] + delta_angle, jntPos[2] - delta_angle,
jntPos[3] + delta_angle, jntPos[4] - delta_angle, jntPos[5] + delta_angle,
jntPos[6] - delta_angle}};
if (time > 60)
{
cmd.setFinished(); // End after 60 seconds
}
//Do NOT use
char* p = new char[64];
return cmd;
};

Why memory allocation affects performance:

  • Heap allocations (e.g., std::vector, Eigen::VectorXd) are very slow
  • At 1 kHz frequency, even small allocations will accumulate and cause system jitter
  • Pre-allocating memory ensures deterministic and real-time system behavior

API Support

The following table is an overview of interface support for each language version.

ModuleAPI FunctionC++Python & C#Android
rokae::RobotBasic OperationsFully SupportedFully SupportedFully Supported
rokae::RobotNon-Real-Time MotionFully SupportedFully SupportedFully Supported
rokae::RobotJog RobotFully SupportedFully SupportedFully Supported
rokae::RobotCommunicationFully SupportedFully SupportedFully Supported
rokae::RobotRL ProjectFully SupportedFully SupportedFully Supported
rokae::RobotCollaborative RelatedFully SupportedPartially SupportedFully Supported
rokae::ModelKinematics CalculationFully SupportedFully SupportedFully Supported
rokae::ForceControlForce Control CommandsFully SupportedFully SupportedFully Supported
rokae::RtMotionControlReal-Time ModeFully SupportedNot SupportedNot Supported
rokae::PlannerPC-Based Path PlanningFully SupportedNot SupportedNot Supported
rokae::xMateModelKinematics and Dynamics CalculationFully SupportedNot SupportedNot Supported