SDK API and HMI Function Correspondence
General APIs
This chapter lists the correspondence between the C++ version of xCore SDK and the Robot Assist interface.
Connect to Robot
Establish a connection with the robot. The robot address is passed when creating the robot instance.
template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::connectToRobot (error_code &ec )
- Parameter: [out] ec: Error code

Disconnect
Disconnect from the robot. The robot motion will be stopped before disconnecting, please pay attention to safety.
void rokae::BaseRobot::disconnectFromRobot (error_code & ec)
-
Parameter: [out] ec: Error code

Query Robot Basic Information
- Parameter: [out] ec: Error code
- Return: Robot basic information (controller version, model, number of axes)
struct Info {
std::string id; ///< Robot uid, can be used to distinguish connected robots
std::string mac; ///< Mac address
std::string version; ///< Controller version
std::string type; ///< Robot model name
int joint_num; ///< Number of axes
};
Info robotInfo(error_code &ec) const noexcept;

Robot Power On/Off and E-Stop Status
Robot power on/off and emergency stop status
PowerState powerState(error_code &ec)
-
Parameter: [out] ec: Error code
-
Return:
-
on - Power on
-
off - Power off
-
estop - Emergency stop
-
gstop - Safety door open
-
![]()

Robot Power On/Off
Robot power on/off. Note: Only robots without external enable switches or teach pendants can be powered on in manual mode.
void setPowerState(bool on, error_code &ec)
- Parameters:
- [in] on: true - Power on | false - Power off
- [out] ec: Error code
![]()
Robot Operation Mode and Switching
Query the current operation mode of the robot
OperateMode operateMode(error_code &ec)
Switch manual/automatic mode
void setOperateMode(OperateMode mode, error_code &ec)
enum class OperateMode {
manual = 0, ///< Manual
automatic = 1, ///< Automatic
unknown = Unknown ///< Unknown (exception occurred)
};
![]()
Query Robot Running Status
Query the current running status of the robot (idle, in motion, drag enabled, etc.)
enum class OperationState {
idle = 0, ///< Robot stationary
jog = 1, ///< Jog status (not moving)
rtControlling = 2, ///< Real-time mode controlling
drag = 3, ///< Drag enabled
rlProgram = 4, ///< RL project running
demo = 5, ///< Demo in progress
dynamicIdentify = 6, ///< Dynamics identification in progress
frictionIdentify = 7, ///< Friction identification in progress
loadIdentify = 8, ///< Load identification in progress
moving = 9, ///< Robot in motion
jogging = 10, ///< Jog in motion
unknown = Unknown ///< Unknown
};
OperationState operationState(error_code &ec)
![]()
Status Description:

Get Current Joint Angles
Current axis angles of the robot, unit: radians
- Parameter: [out] ec: Error code
- Return: Axis angle values
std::array<double, DoF> jointPos(error_code &ec)


Joint Velocity
Current joint velocity of the robot, unit: radians/second
- Parameter: [out] ec: Error code
- Return: Joint velocity
std::array<double, DoF> jointVel(error_code &ec)

Get Joint Torque
Joint force sensor values, unit: NM
- Parameter: [out] ec: Error code
- Return: Joint torque values
std::array<double, DoF> jointTorque(error_code &ec)

Query Controller Logs
Query the latest logs from the controller
- Parameters:
- [in] count Number of queries, maximum is 10
- [in] level Specify log level, empty set means no specification
- [out] ec: Error code
- Return: Log information
std::vector< LogInfo > rokae::BaseRobot::queryControllerLog ( unsigned count,const std::set< LogInfo::Level > & level,error_code & ec )

Set Collision Detection Related Parameters, Enable/Disable Collision Detection Function
Set collision detection related parameters, enable collision detection function
- Parameters:
- [in] sensitivity Collision detection sensitivity, range 0.01-2.0
- [in] behaviour Robot behavior after collision, supports stop1 (safe stop, stop0 and stop1 handling methods are the same) and stop2 (trigger pause), suppleStop (compliant stop)
- [in] fallback_compliance
- When the post-collision behavior is safe stop or trigger pause, this parameter means the fallback distance after collision, unit: meters
- When the post-collision behavior is compliant stop, this parameter means the compliance, range [0.0, 1.0]
- [out] ec: Error code
void enableCollisionDetection(const std::array<double, DoF> &sensitivity, StopLevel behaviour,
double fallback_compliance, error_code &ec) noexcept;
Disable collision detection function
void disableCollisionDetection(error_code &ec)

Frame Calibration
Frame calibration (N-point calibration)
- Note: Calibration methods and precautions supported by each frame type:
- Tool frame: Three-point/four-point/six-point calibration method
- Workpiece frame: Three-point calibration. The calibration result will not be transformed relative to the user frame, i.e., if it is an external workpiece, the returned result is relative to the base frame.
- Base frame: Six-point calibration. Please ensure dynamics constraints and feedforward are turned off before calibration. If calibration is successful (no error code), the controller will automatically save the calibration result, which will take effect after restarting the controller.
- Rail base frame: Three-point calibration. If calibration is successful (no error code), the controller will automatically save the calibration result, which will take effect after restarting the controller.
- Parameters:
- [in] points List of axis angles, list length is N. For example, when using three-point method to calibrate tool frame, 3 sets of axis angles should be passed. Axis angles are in radians.
- [in] is_held true - Robot handheld | false - External. Only affects tool/workpiece calibration
- [in] base_aux Auxiliary point used in base frame calibration, unit [meters]
- [out] ec: Error code
- Return: Calibration result, valid when error code is not set
template<WorkType Wt, unsigned short DoF>
FrameCalibrationResult rokae::Robot_T< Wt, DoF >::calibrateFrame (
FrameType type,
const std::vector< std::array< double, DoF > > &points,
bool is_held,
error_code &ec,
const std::array< double, 3 > & base_aux = {} )



Set Rail Parameters
-
Template parameter: Parameter type
-
Parameters:
-
[in] name: Parameter name, see value description
-
[in] value:
-
Parameter: Parameter Name Data Type Enable enable bool Base Frame baseFrame Frame Rail Name name std::string Encoder Resolution encoderResolution int Reduction Ratio reductionRatio double Motor Max Speed(rpm) motorSpeed int Soft Limit(m), [Lower,Upper] softLimit std::vector<double>Motion Range(m), [Lower,Upper] range std::vector<double>Max Speed(m/s) maxSpeed double Max Acceleration(m/s^2) maxAcc double Max Jerk(m/s^3) maxJerk double
-
template<typename R>
void rokae::setRailParameter(const std::string &name, R value, error_code &ec)
Read rail parameters
- Template parameter: Parameter type
- Parameters:
- [in] name Parameter name, see setRailParameter()
- [out] value Parameter value, see setRailParameter()
- [out] ec: Error code, returns error code if parameter name does not exist or data type does not match
template<typename R>
void getRailParameter(const std::string &name, R &value, error_code &ec) noexcept;

Robot Running Speed Adjustment
Dynamically adjust robot motion speed, effective in non-real-time mode.
- Parameters:
- [in] scale: Speed ratio of motion commands, range 0.01 - 1. When scale is set to 1, the robot will move at the original path speed.
- [out] ec: Error code
void rokae::BaseRobot::adjustSpeedOnline(double scale, error_code &ec)

Communication Related
Set Input Simulation Mode
state true - Enable | false - Disable
void setSimulationMode(bool state, error_code &ec)

Set xPanel External Power Supply Mode
xPanel settings can configure the power supply mode for the robot's end tool. This function is only applicable to collaborative robots xMate CR SR series.
struct xPanelOpt {
/*
@brief Power supply mode
*/
enum Vout {
off, ///< No output
reserve, ///< Reserved
supply12v, ///< Output 12V
supply24v, ///< Output 24V
};
};
void setxPanelVout(xPanelOpt::Vout opt, error_code& ec)

Collaboration Related
Enable Drag & Disable Drag
Enable drag
- space Drag space. Joint space drag only supports free drag type
- type Drag type
- ec Error code
void enableDrag(DragParameter::Space space, DragParameter::Type type, error_code& ec, bool enable_drag_button = false)
Disable drag
void disableDrag(error_code& ec)

Path Operations
Start recording path & Stop recording path & Cancel recording & Save path & Path playback & Delete saved path

Force Sensor Calibration
Force sensor calibration. The calibration process takes about 100ms, this function will not block waiting for calibration to complete. Before calibration, the correct load needs to be set through setToolset() (Toolset::load), otherwise it will affect the accuracy of the calibration result.
- all_axes true - Calibrate all axes | false - Single axis calibration
- Axis index, range [0, DoF), only effective when single axis calibration
- ec Error code
void calibrateForceSensor(bool all_axes, int axis_index, error_code &ec)

SDK API and RL Instruction Correspondence
Joint Motion MoveAbsJ
- Target joint angles
- End linear velocity, unit mm/s, joint velocity is divided into several intervals based on end linear velocity, see setDefaultSpeed()
- Turn zone, unit mm
MoveAbsJCommand(JointPosition target, double speed = USE_DEFAULT, double zone = USE_DEFAULT);
RL Instruction: MoveAbsJ
Description:
MoveAbsJ (Move Absolute Joint) is used to move the robot and external axes to a position defined by joint angles, used for quick positioning or moving the robot to a precise joint angle. All axes move synchronously, the robot end moves along an irregular curve, please pay attention to whether there is a risk of collision. The tool parameter used in the MoveAbsJ instruction does not affect the robot's end position, but the controller still needs the tool parameter for dynamics calculation.
Joint Motion MoveJ
- Target Cartesian point
- End linear velocity, unit mm/s, joint velocity is divided into several intervals based on end linear velocity, see setDefaultSpeed()
- Turn zone, unit mm
MoveJCommand(CartesianPosition target, double speed = USE_DEFAULT, double zone = USE_DEFAULT);
RL Instruction: MoveJ
Description:
MoveJ (Move The Robot By Joint Movement) is used when there is no requirement for the robot end motion trajectory,
to make the robot quickly move from one point to another. All axes move synchronously, the robot end moves along an irregular curve, please pay attention to whether there is a risk of collision.
The biggest difference between MoveJ instruction and MoveAbsJ is the format of the given target point. The target point of MoveJ is the spatial pose of the tool (TCP) rather than joint axis angles.
End Linear Trajectory MoveL
- Target Cartesian point
- End linear velocity, unit mm/s, joint velocity is divided into several intervals based on end linear velocity, see setDefaultSpeed()
- Turn zone, unit mm
MoveLCommand(CartesianPosition target, double speed = USE_DEFAULT, double zone = USE_DEFAULT);
RL Instruction: MoveL
Description:
Used to move the tool center point TCP along a straight line to the given target position.
When the start and end poses are different, the pose will rotate synchronously with the position to the end pose. Since translation and rotation speeds are specified separately, to ensure the specified speed limit is not exceeded, the final motion time of the MoveL instruction depends on the one with the longer time for pose, position, and arm angle changes. Therefore, when executing certain specific trajectories (such as small displacement but large pose change), if the robot motion speed is obviously too slow or too fast, please check whether the rotation speed setting is reasonable. When you need to keep the tool center point TCP stationary and only adjust the tool pose, you can achieve this by specifying start and end points with the same position but different poses for MoveL.
Arc Trajectory MoveC
- Target point
- Auxiliary point
- End linear velocity, unit mm/s, joint velocity is divided into several intervals based on end linear velocity, see setDefaultSpeed()
- Turn zone, unit mm
MoveCCommand(CartesianPosition target, CartesianPosition aux, double speed = USE_DEFAULT, double zone = USE_DEFAULT);
RL Instruction: MoveC
Description:
MoveC (Move Circle) is used to move the tool center point TCP along an arc through the intermediate auxiliary point to the given target position. When the start and end poses are different, the pose will rotate synchronously with the position to the end pose, and the auxiliary point pose does not affect the arc motion process. Since translation and rotation speeds are specified separately, to ensure the specified speed limit is not exceeded, the final motion time of the MoveC instruction depends on the one with the longer time for pose, position, and arm angle changes. Therefore, under certain specific trajectories (such as small displacement but large pose change), if the robot motion speed is obviously too slow or too fast, please check whether the rotation speed setting is reasonable.
Full Circle Trajectory MoveCF
- Target point
- Auxiliary point
- End linear velocity, unit mm/s
- Turn zone, unit mm
- Execution angle, unit radians
MoveCFCommand(const CartesianPosition &target, const CartesianPosition &aux, double angle, double speed = USE_DEFAULT, double zone = USE_DEFAULT);
RL Instruction: MoveCF
Description:
MoveCF (Move Circle Full) is used to move and rotate the tool center point TCP along a circular path determined by the start point and two auxiliary points, with the given full circle execution angle. The end point of the MoveCF full circle motion is determined by the full circle execution angle, and the two auxiliary points are only used to determine the spatial position of the circular path. During the full circle motion, the pose will change in the manner specified by the parameters, and the auxiliary point poses do not affect the pose during the full circle motion. The final motion time of the MoveCF instruction only depends on the time of position change. Therefore, in the case of small circle radius, please check whether the motion speed setting is reasonable to avoid the situation of too fast pose rotation.
Spiral Trajectory MoveSP
- target End pose
- r0 Initial radius [m]
- rStep Radius change per unit angle of rotation [m/rad]
- angle Total rotation angle [rad]
- dir Rotation direction, true - clockwise | false - anticlockwise
- speed End linear velocity, unit mm/s
MoveSPCommand(const CartesianPosition &target, double r0, double rStep, double angle, bool dir, double speed = USE_DEFAULT);
RL Instruction: MoveSP
Description:
MoveSP (Move Spiral) is used to draw an Archimedean spiral in a plane parallel to the xy plane of the workpiece coordinate system, with the specified initial radius, rotation increment rate, total rotation angle, and rotation direction. During the motion, the pose linearly changes to the specified pose in the target point. Note: When the MoveSP instruction is paused during motion and continues to run, it will regenerate the path from the current point as the start point, and will not continue the previous path.
Force Control Initialization
-
frame_type Force control coordinate system, supports world/wobj/tool/base/flange. Tool and workpiece coordinate systems use the coordinate system set by setToolset()
-
ec Error code
void fcInit(FrameType frame_type, error_code &ec)
RL Instruction: FcInit
Description:
Used for some initialization work before force control is enabled, such as setting workpiece, tool, and force control coordinate system.
Set Impedance Control Type
-
type 0 - Joint impedance | 1 - Cartesian impedance
-
ec Error code
void setControlType(int type, error_code &ec)
RL Instruction: SetControlType (ctrl_type)
Description:
ctrl_type, data type: int, impedance control type,
supports:
0: Joint impedance
1: Cartesian impedance
Set Cartesian Impedance Stiffness
-
stiffness In order: X Y Z direction impedance force stiffness [N/m], X Y Z direction impedance torque stiffness [Nm/rad]
-
ec Error code
void setCartesianStiffness(const std::array<double, 6> &stiffness, error_code &ec)
RL Instruction:
SetCartCtrlStiffVec trans(stiff_x,trans_stiff_y,trans_stiff_z,rot_stiff_x,rot_stiff_y,rot_stiff_z);
trans_stiff_x,data type:double,X direction Cartesian impedance force stiffness,unit:N/m。
trans_stiff_y,data type:double,Y direction Cartesian impedance force stiffness,unit:N/m。
trans_stiff_z,data type:double,Z direction Cartesian impedance force stiffness,unit:N/m。
rot_stiff_x,data type:double,X direction Cartesian impedance torque stiffness,unit:N.m/rad。
rot_stiff_y,data type:double,Y direction Cartesian impedance torque stiffness,unit:N.m/rad。
rot_stiff_z,data type:double,Z direction Cartesian impedance torque stiffness,unit:N.m/rad。
Set Cartesian Nullspace Impedance Stiffness
-
stiffness Range [0,4], greater than 4 will default to 4, unit Nm/rad
-
ec Error code
void setCartesianNullspaceStiffness(double stiffness, error_code &ec)
RL Instruction:
SetCartNsStiff(cart_ns_stiff);
cart_ns_stiff,data type:double,Cartesian nullspace impedance stiffness,value range(0~4),unit:Nm/rad。
Set Joint Impedance Stiffness
- stiffness Stiffness of each axis
- ec Error code
void setJointStiffness(const std::array<double, DoF> &stiffness, error_code &ec)
RL Instruction:
SetJntCtrlStiffVec( jnt1_stiff,jnt2_stiff,jnt3_stiff,jnt4_stiff,jnt5_stiff, jnt6_stiff,jnt7_stiff);
Jnt1_stiff,data type:double,Joint 1 impedance stiffness,unit:Nm/rad。
Jnt2_stiff,data type:double,Joint 2 impedance stiffness,unit:Nm/rad。
Jnt3_stiff,data type:double,Joint 3 impedance stiffness,unit:Nm/rad。
Jnt4_stiff,data type:double,Joint 4 impedance stiffness,unit:Nm/rad。
Jnt5_stiff,data type:double,Joint 5 impedance stiffness,unit:Nm/rad。
Jnt6_stiff,data type:double,Joint 6 impedance stiffness,unit:Nm/rad。
Jnt7_stiff,data type:double,Joint 7 impedance stiffness,unit:Nm/rad。//When setting 6-axis robot, this parameter defaults to 0.
Set Joint Desired Torque
- torque Torque value, range [-30,30], unit Nm
- ec Error code
void setJointDesiredTorque(const std::array<double, DoF> &torque, error_code &ec)
RL Instruction SetJntTrqDes (tau_d1,tau_d2,tau_d3,tau_d4,tau_d5,tau_d6,tau_d7);
tau_d1,data type:double,Joint 1 desired torque,value range(-30~30),unit N.m。
tau_d2,data type:double,Joint 2 desired torque,value range(-30~30),unit N.m。
tau_d3,data type:double,Joint 3 desired torque,value range(-30~30),unit N.m。
tau_d4,data type:double,Joint 4 desired torque,value range(-30~30),unit N.m。
tau_d5,data type:double,Joint 5 desired torque,value range(-30~30),unit N.m。
tau_d6,data type:double,Joint 6 desired torque,value range(-30~30),unit N.m。
tau_d7,data type:double,Joint 7 desired torque,value range(-30~30),unit N.m。//When setting 6-axis robot, this parameter defaults to 0.
Set Cartesian Desired Force/Torque
- value In order: X Y Z direction Cartesian desired force, range [-60,60], unit N; X Y Z direction Cartesian desired torque, range [-10,10], unit Nm
- ec Error code
void setCartesianDesiredForce(const std::array<double, 6> &value, error_code &ec)
RL Instruction:SetCartForceDes (force_x,force_y,force_z,torque_x,torque_y,torque_z);
force_x,data type:double,X direction Cartesian desired force,value range(-60~60),unit N。
force_y,data type:double,Y direction Cartesian desired force,value range(-60~60),unit N。
force_z,data type:double,Z direction Cartesian desired force,value range(-60~60),unit N。
torque_x,data type:double,X direction Cartesian desired torque,value range(-10~10),unit N.m。
torque_y,data type:double,Y direction Cartesian desired torque,value range(-10~10),unit N.m。
torque_z,data type:double,Z direction Cartesian desired torque,value range(-10~10),unit N.m。
Set Sine Search Motion Rotating Around Single Axis
After setting the impedance control type to Cartesian impedance (i.e., setControlType(1)), it takes effect before calling startOverlay().
The upper limits of search motion amplitude and search motion frequency vary by model, please refer to the "xCore Control System Manual" for instructions on the SetSineOverlay instruction.
- line_dir Search motion reference axis: 0 - X | 1 - Y | 2 - Z
- amplify Search motion amplitude, unit Nm
- frequency Search motion frequency, unit Hz
- phase Search motion phase, range [0, PI], unit radians
- bias Search motion bias, range [0, 10], unit Nm
- ec Error code
void setSineOverlay(int line_dir, double amplify, double frequency, double phase,double bias, error_code &ec)
RL Instruction:SetSineOverlay( line_dir, amplify, frequncy, phase, bias);
line_dir,data type:int,search motion reference axis,supports
0:reference direction is X axis
1:reference direction is Y axis
2:reference direction is Z axis
Amplify,data type:double,search motion amplitude,unit N.m。
Frequncy,data type:double,search motion frequency,unit Hz。
Phase,data type:double,search motion phase,value range(-3.14~3.14),unit rad。
Bias,data type:double,search motion bias,value range(-10~10),unit N.m。
Set Lissajous Search Motion in Plane
After setting the impedance control type to Cartesian impedance (i.e., setControlType(1)), it takes effect before calling startOverlay().
- plane Search motion reference plane: 0 - XY | 1 - XZ | 2 - YZ
- amplify_one Search motion direction one amplitude, range [0, 20], unit Nm
- frequency_one Search motion direction one frequency, range [0, 5], unit Hz
- amplify_two Search motion direction two amplitude, range [0, 20] unit Nm
- frequency_two Search motion direction two frequency, range [0, 5], unit Hz
- phase_diff Search motion phase difference between two directions, range [0, PI], unit radians
- ec Error code
void setLissajousOverlay(int plane, double amplify_one, double frequency_one, double amplify_two,double frequency_two, double phase_diff, error_code &ec)
RL Instruction:SetLissajousOverlay(plane, amplify_one, frequncy_one, amplify_two, frequncy_two, phase_diff);
Plane,data type:int,search motion reference plane,supports
0:reference plane is XY plane
1:reference plane is XZ plane
2:reference plane is YZ plane
amplify_one,data type:double,search motion direction one amplitude,value range(-20~20),unit N.m。
frequncy_one,data type:double,search motion direction one frequency,value range(0~5),unit Hz。
amplify_two,data type:double,search motion direction two amplitude,value range(-20~20),unit N.m。
frequncy_two,data type:double,search motion direction two frequency,value range(0~5),unit Hz。
phase_diff,data type:double,search motion phase difference between two directions,value range(-3.14~3.14),unit rad
Set Load Used by Force Control Module
- load Load
- ec Error code
void setLoad(const Load &load, error_code &ec)
RL Instruction:SetLoad(m,rx,ry,rz,Ixx,Iyy,Izz );
M,data type:double,load mass,unit:kg,range(0~25);
Rx,data type:double,distance of load center of mass in flange coordinate system x direction,unit:mm,range(-300,300);
Ry,data type:double,distance of load center of mass in flange coordinate system y direction,unit:mm,range(-300,300);
Rz,data type:double,distance of load center of mass in flange coordinate system z direction,unit:mm,range(-300,300);
Ixx,data type:double,principal moment of inertia of load center of mass x axis,unit:kg*mm^2,range(0,100000);
Iyy,data type:double,principal moment of inertia of load center of mass y axis,unit:kg*mm^2,range(0,100000);
Izz,data type:double,principal moment of inertia of load center of mass z axis,unit:kg*mm^2,range(0,100000);
Other Force Control Instruction SDK API and RL Correspondence
| Function | SDK API | RL Instruction |
|---|---|---|
| Enable previously set search motion | startOverlay | StartOverlay |
| Pause search motion | pauseOverlay | PauseOverlay |
| Restart paused search motion | restartOverlay() | RestartOverlay |
| Stop search motion | stopOverlay | StopOverlay |
| Enable force control | fcStart | FcStart |
| Stop force control | fcStop | FcStop |
| Set termination condition related to contact force | setForceCondition | FcCondForce |
| Set termination condition related to contact torque | setTorqueCondition | FcCondTorque |
| Set termination condition related to contact position | setPoseBoxCondition | FcCondPosBox |
| Activate set termination condition and wait | waitCondition | FcCondWaitWhile |
| Enable/Disable force control module protection monitoring | fcMonitor | FcMonitor |
| Set maximum axis speed in force control mode | setJointMaxVel | SetFcJointVelMax |
| Set maximum end speed relative to base frame in force control mode | setCartesianMaxVel | SetFcCartVelMax |
| Set maximum axis momentum in force control mode | setJointMaxMomentum | SetFcJointMomentumMax |
| Set maximum axis kinetic energy in force control mode | setJointMaxEnergy | SetFcJointEnergyMax |
Path Playback
SDK API:
-
name Path name to playback
-
rate Playback rate, should be less than 3.0, 1 is the original path rate. Note that when rate is greater than 1, driver following errors may occur
-
ec Error code
void replayPath(const std::string& name, double rate, error_code& ec)
RL Instruction:ReplayPath( path [, rate] [, wobj/tool] );
Path,data type:path,drag playback path type,defined in path list,drag teaching recording。
Rate,data type:double,playback percentage,range 0.01~3.00。0.01 means running at 1% of the drag speed;
1.00 means 100% speed original speed playback;3.00 means 300% speed playback。
wobj/tool,data type:Tool|Workpiece。Specify that the end device of the multi-motion playback instruction is a certain tool or workpiece,during playback
the robot will change the playback control parameters according to the corresponding device to improve running stability