Skip to main content

Non-Real-Time Command Common Issues

Non-real-time interface errors are all fed back through error_code. During debugging and actual use, be sure to check the error_code for each call.

Robot Does Not Move After Issuing Motion Command

Phenomenon: Robot does not move after calling moveAppend + moveStart. Troubleshooting steps:

  1. Confirm whether function call was successful Check method:
std::string id;
error_code ec;
MoveLCommand cmd {};
robot.moveAppend(cmd, id, ec);
if(ec) {
// Command issuance error
}
robot.moveStart(ec);
if(ec) {
// Start motion error
}

Be sure to check for error codes after each SDK function call. Motion commands will return error codes in the following situations:

  • Robot is not powered on, or in a state where it cannot move such as emergency stop pressed
  • Drag mode is enabled/RL project is running, etc., robot is in a non-idle state
  • More than 100 commands passed in a single moveAppend call
  1. Receive and check motion errors

If errors occur during motion, such as limit exceeded, singularity, etc., they can be received as follows:

void printInfo(const rokae::EventInfo &info) {
using namespace rokae::EventInfoKey::MoveExecution;
print(std::cout, "[Motion Execution Info] ID:", std::any_cast<std::string>(info.at(ID)), "Index:", std::any_cast<int>(info.at(WaypointIndex)),
"Completed: ", std::any_cast<bool>(info.at(ReachTarget)) ? "YES": "NO", std::any_cast<error_code>(info.at(Error)),
std::any_cast<std::string>(info.at(Remark)));
}
// Set up motion execution information listener
robot.setEventWatcher(Event::moveExecution, printInfo, ec);

It is recommended to print errors or output logs during debugging. If connected to a teach pendant, controller logs will also be reported, as shown below: SDK Motion Command Error Log

  1. How to resolve motion errors

Motion errors are generally referred to as unreachable. The points in the example program are given based on different models; most of the time, to run smoothly, you need to confirm that the points are reachable.

First confirm the meaning and units of the point values in the program:

// MoveAbsJ command target point is joint angles, unit is radians
MoveAbsJCommand moveAbsj({0.0, 0.2215, 1.4779, 0.0, 1.267, 0.0});
// MoveL and MoveJ command target points are Cartesian poses, first three numbers are XYZ position, unit is meters; last three numbers are orientation, unit is radians
MoveLCommand moveL({0.562, 0, 0.432, M_PI, 0, -M_PI});
MoveJCommand moveJ({0.2434, -0.314, 0.591, 1.5456, 0.314, 2.173});

If positions appear in the hundreds or tens, the unit was mistakenly taken as millimeters; if angles appear as 180, it must be degree values.

After confirming the point values are correct, refer to How to Resolve Unreachable Points

How to Resolve Unreachable Points

Joint points are generally reachable as long as they do not exceed joint limits. Here we mainly discuss Cartesian point unreachable issues

  • All Cartesian points are tool relative to workpiece, so if tool and workpiece are set, the points also need to be adjusted
  • Cannot exceed the robot arm's working range
  • Cartesian space motions such as MoveL/MoveC require that no singularities exist at any point along the entire line. Being able to jog there does not mean the straight-line trajectory can be traversed, which is directly related to the starting position. If encountering singularities, you need to adjust the points or switch to MoveJ
  • For MoveL/MoveJ, axis configuration data (confdata) also needs attention. confdata is only available for taught points and cannot be calculated.
    • For taught points, the cartPosture() function returns results containing confdata, which must also be included in subsequent motion commands.
    • For non-taught points, confdata cannot be determined, so you need to tell the controller not to use confdata for inverse kinematics calculation:
// Disable using conf
robot.setDefaultConfOpt(false, ec);

This setting can also be seen on the teach pendant: Teach Pendant Default conf Setting

Robot Stops Before Reaching the Given Position

Troubleshooting steps:

  • First check if errors occurred during motion, refer to the previous two sections
  • If no errors, it may be a program logic issue. The Robot class will pause robot motion when destructed. So if the program exits while the robot is still moving, it will also cause the robot to stop before reaching the position. Solution: Refer to methods like waitRobot() and waitForFinish() in the examples to block the process and wait for motion to complete.

Motion Speed is Very Slow/Cannot Reach Expected Speed

  • Check program speed. Program speed can be set as follows:
// 1 represents 100% speed ratio
robot.adjustSpeedOnline(1, ec);

It can also be seen on the teach pendant: Teach Pendant Program Speed

  • Check whether setDefaultSpeed(), cmd.speed usage is correct

Is There an Upper Limit on the Number of Commands Issued

There is no quantity limit. After issuing through moveAppend, commands are sent directly to the controller. If there are too many commands, the SDK itself will cache some and be responsible for continuously sending them to the controller. This default number is 300, which can be set to a maximum of 1000 via setMaxCacheSize.

Using Simultaneously with RobotAssist

Currently, if using xCore SDK to control the robot, it will not restrict control through RobotAssist. Some robot states changed through xCore SDK will also be reflected on the Robot Assist interface; some project execution and motion control are separated. The general summary is as follows:

CategoryImplementation
Components that will sync updates- Bottom status bar: Manual/Auto, robot status, power on/off;
- Status monitoring window;
- Log reporting;
Components controllable by both parties, i.e., modifications through RobotAssist will take effect- RL project execution speed and cycle/single mode;
- Non-real-time mode motion pause;
- Tool workpiece group: Changing tool workpiece selected in the upper right corner of RobotAssist will change toolset; setting tool workpiece via setToolset will display "toolx ", "wobjx " in the upper right corner
Components that will not sync updates, including but not limited to- Issued motion commands cannot be executed by clicking the start button;
- Loaded RL project, as well as lookahead pointer, motion pointer, etc., will not be displayed in sync;
- Most robot settings interface function open status and set values, etc.;

The recommended control method is a single control source to avoid confusion.