Skip to main content

Methods

1 Basic Robot Operations and Information Query

connectToRobot() [1/2]

template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::connectToRobot (error_code &ec )

Establish connection with the robot. The robot address is passed when creating the robot instance.

  • Parameter: [out] ec: Error code

connectToRobot() [2/2]

template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::connectToRobot (const std::string &remoteIP,const std::string &localIP = "" )

Connect to the robot

  • Parameters:
    • remoteIP Robot IP address
    • localIP Local address. Used for real-time mode data transmission, optional; PCB3/4 axis models do not support |

disconnectFromRobot()

void rokae::BaseRobot::disconnectFromRobot (error_code & ec)

Disconnect from the robot. Will stop robot motion before disconnecting, please pay attention to safety.

  • Parameter: [out] ec: Error code

setConnectionHandler()

void setConnectionHandler(const std::function<void(bool)> &handler)

Set connection disconnection callback function

  • Parameter: [in] handler Callback function, parameter is bool, true-connected | false-disconnected

robotInfo()

Info rokae::BaseRobot::robotInfo (error_code &ec ) const

Query basic robot information

  • Parameter: [out] ec: Error code
  • Return: Basic robot information (controller version, model, number of axes)

powerState()

PowerState rokae::BaseRobot::powerState(error_code &ec) const

Robot power on/off and emergency stop status

  • Parameter: [out] ec: Error code
  • Return:
    • on - Powered on
    • off - Powered off
    • estop - Emergency stop
    • gstop - Safety door open

setPowerState()

void rokae::BaseRobot::setPowerState (bool on, error_code & ec)

Robot power on/off. Note: Only robots without external enable switch or teach pendant can be powered on in manual mode.

  • Parameters:
    • [in] on: true-Power on|false-Power off
    • [out] ec: Error code

operateMode()

OperateMode rokae::BaseRobot::operateMode (error_code & ec)const

Query current robot operation mode

  • Parameter: [out] ec: Error code
  • Return: Manual | Automatic

setOperateMode()

void rokae::BaseRobot::setOperateMode ( OperateMode mode, error_code & ec)

Switch between manual and automatic mode

  • Parameters:
    • [in] mode: manual - Manual/ automatic - Automatic
    • [out] ec: Error code

rebootSystem()

void rebootSystem(error_code& ec)

Restart the industrial PC. Note: Restart operation is not allowed in automatic mode, powered off state, motion and non-idle state.

  • Parameters:
    • [out] ec: Error code

shutdownSystem()

void shutdownSystem(error_code& ec)

Shut down the industrial PC. Restart operation is not allowed in automatic mode, powered off state, motion and non-idle state. The controller software can only be restarted after the control cabinet is powered off and then powered on again.

  • Parameters:
    • [out] ec: Error code

operationState()

OperationState rokae:BaseRobot::operationState ( error_code & ec) const

Query current robot running status (idle, in motion, drag enabled, etc.)

  • Parameter: [out] ec: Error code
  • Return: Running status enumeration class

posture()

std::array&lt; double,6&gt;rokae::BaseRobot::posture(CoordinateType ct, error_code & ec )

Get current pose of robot flange or end effector

  • Parameters:
    • [in] ct Coordinate system type
      • flangeInBase: Flange relative to base coordinate system;
      • endInRef: End effector relative to external reference coordinate system. For example, when handheld tool and external workpiece are set, this coordinate system type returns the coordinates of the tool relative to the workpiece coordinate system.
    • [out] ec: Error code
  • Return: Double array, [X, Y, Z, Rx, Ry, Rz], where translation units are meters and rotation units are radians

cartPosture()

CartesianPosition rokae::BaseRobot::cartPosture(CoordinateType ct, error_code & ec )

Get current pose of robot flange or end effector

  • Parameters:
    • [in] ct Coordinate system type
    • [out] ec: Error code
  • Return: Current Cartesian position

jointPos() [1/2]

template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointPos ( error_code & ec )

Current robot joint angles, unit: rad

  • Parameter: [out] ec: Error code
  • Return: Joint angle values

jointPos() [2/2]

std::vector<double> rokae::BaseRobot::jointPos (error_code & ec)

Current robot joint angles, robot body + external axes, unit: [rad/m], external axis guide rail, unit: [rad/m]

  • Parameter: [out] ec: Error code
  • Return: Joint angle values and external axis values

jointVel() [1/2]

template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointVel ( error_code & ec )

Current robot joint velocity, unit: radians/second

  • Parameter: [out] ec: Error code
  • Return: Joint velocity

jointVel() [2/2]

std::vector<double> rokae::BaseRobot::jointVel(error_code & ec)

Current robot joint velocity, robot body + external axes, unit: radians/second, external axis unit: meters/second

  • Parameter: [out] ec: Error code
  • Return: Joint velocity

getStateList()

StateList rokae::BaseRobot::getStateList(error_code &ec)

Query current position, IO signals, operation mode, speed override value

  • Parameter: [out] ec: Error code
  • Return: Query result

jointTorque()

template<WorkType Wt, unsigned short DoF>
std::array< double, DoF > rokae::Robot_T< Wt, DoF >::jointTorque ( error_code &ec )

Joint force sensor values, unit: Nm

  • Parameter: [out] ec: Error code
  • Return: Torque values

baseFrame()

std::array< double, 6 > rokae::BaseRobot::baseFrame ( error_code &ec ) const

User-defined base coordinate system, relative to world coordinate system

  • Parameter: [out] ec: Error code
  • Return: Double array, [X, Y, Z, Rx, Ry, Rz], where translation units are meters and rotation units are radians

setBaseFrame()

void rokae::BaseRobot::setBaseFrame(const Frame &frame, error_code &ec)

Set base coordinate system. Only saves values after setting, takes effect after controller restart.

  • Parameters:
    • [in] frame Coordinate system, default uses custom installation method
    • [out] ec: Error code

toolset()

Toolset rokae::BaseRobot::toolset (std::error_code & ec ) const

Query current tool and workpiece group information

Note: This tool and workpiece group is only for SDK motion control use, not related to RL projects

  • Parameter: [out] ec: Error code
  • Return: See Toolset data structure

setToolset()

void rokae::BaseRobot::setToolset ( const Toolset & toolset,error_code & ec )

Set tool and workpiece group information

Note: This tool and workpiece group is only for SDK motion control use, not related to RL projects. After setting, RobotAssist will display "toolx", "wobjx" in the upper right corner, and the end coordinate displayed in status monitoring will also change. In addition to this interface, if the default tool and workpiece are changed through RobotAssist (upper right corner option), this tool and workpiece group will also change accordingly.

  • Parameters:
    • [in] toolset Tool and workpiece group information
    • [out] ec: Error code

setToolset()

void rokae::BaseRobot::setToolset (const std::string &toolName, const std::string &wobjName,error_code &ec )

Use created tools and workpieces to set tool and workpiece group information

Note: Setting prerequisites: An RL project has been loaded and tools and workpieces have been created. Otherwise, only the default tools and workpieces can be set, namely "tool0" and "wobj0". A set of tools and workpieces cannot be handheld or external at the same time; if there is a conflict, the tool position shall prevail. For example, if both tool and workpiece are handheld, no error will be returned, but the workpiece coordinate system becomes external.

  • Parameters:
    • [in] toolName Tool name
    • [in] wobjName Workpiece name
    • [out] ec: Error code

calcIk() [1/2]

template<unsigned short DoF>
JointArray rokae::Model_T< DoF >::calcIk (CartesianPosition posture,error_code &ec )

Calculate inverse kinematics based on pose

  • Parameters:
    • [in] posture Robot end effector pose, relative to external reference coordinate system
    • [out] ec: Error code
  • Return: Joint angles, unit: radians

calcIk() [2/2]

template<unsigned short DoF>
JointArray rokae::Model_T< DoF >::calcIk (CartesianPosition posture, const Toolset & toolseterror_code &ec )

Calculate inverse kinematics based on pose under given tool and workpiece coordinate system

  • Parameters:
    • [in] posture Robot end effector pose, relative to external reference coordinate system
    • [in] toolset Tool and workpiece group information
    • [out] ec: Error code
  • Return: Joint angles, unit: radians

calcFk()

template<unsigned short DoF>
CartesianPosition rokae::Model_T< DoF >::calcFk ( const JointArray & joints,error_code & ec )

Calculate forward kinematics based on joint angles

  • Parameters:
    • [in] joints Joint angles, unit: radians
    • [out] ec: Error code
  • Return: Robot end effector pose, relative to external reference coordinate system

calcFk()

template<unsigned short DoF>
CartesianPosition rokae::Model_T< DoF >::calcFk ( const JointArray & joints, const Toolset & toolset error_code & ec )

Calculate forward kinematics based on joint angles under given tool and workpiece coordinate system

  • Parameters:
    • [in] joints Joint angles, unit: radians
    • [in] toolset Tool and workpiece group information
    • [out] ec: Error code
  • Return: Robot end effector pose, relative to external reference coordinate system

calcAllIkSolutions()

std::vector<std::vector<double>> calcAllIkSolutions(const CartesianPosition &posture, std::vector<std::vector<int>> &confs, error_code &ec) noexcept;

Calculate all inverse kinematics solutions for Cartesian pose, supports all models except xMateSR (XMS).

  • Parameters

    • [in] posture Cartesian pose, flange relative to base coordinate system. Other coordinate systems need to be converted by yourself.
    • [out] confs Corresponding confdata, valid when error code is 0
    • [out] ec Error code, including inverse kinematics calculation failure errors: -50102 Singularity | -50114 Exceeds limit | -50519 Out of range | -50002 Other inverse kinematics errors
  • Return: Inverse kinematics results, unit radians, valid when error code is 0

setToolset()

void rokae::BaseRobot::setToolset (const std::string &toolName, const std::string &wobjName,error_code &ec )

Use created tools and workpieces to set tool and workpiece group information

  • Note: Setting prerequisites:
    1. To use tools and workpieces created in RL project: Need to load the corresponding RL project first;
    2. Global tools and workpieces: No need to load project, call directly. e.g. setToolset("g_tool_0", "g_wobj_0") A set of tools and workpieces cannot be handheld or external at the same time; if there is a conflict, the tool position shall prevail. For example, if both tool and workpiece are handheld, no error will be returned, but the workpiece coordinate system becomes external.
  • Parameters:
    • [in] toolName Tool name
    • [in] wobjName Workpiece name
    • [out] ec: Error code

calibrateFrame()

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 = {} )

Coordinate system calibration (N-point calibration)

  • Note: Calibration methods and precautions supported by each coordinate system type:
    1. Tool coordinate system: Three-point/four-point/six-point calibration method
    2. Workpiece coordinate system: Three-point calibration. The calibration result will not be transformed relative to the user coordinate system, that is, if it is an external workpiece, the returned result is relative to the base coordinate system.
    3. Base coordinate system: Six-point calibration. Please ensure that dynamic constraints and feedforward are turned off before calibration. If calibration is successful (no error code), the controller will automatically save the calibration result, which takes effect after controller restart.
    4. Guide rail base coordinate system: Three-point calibration. If calibration is successful (no error code), the controller will automatically save the calibration result, which takes effect after controller restart.
  • Parameters:
    • [in] points List of joint angles, list length is N. For example, when using three-point method to calibrate tool coordinate system, 3 sets of joint angles should be passed. Joint angle unit is radians.
    • [in] is_held true - Robot handheld | false - External. Only affects calibration of tools/workpieces
    • [in] base_aux Auxiliary point used for base coordinate system calibration, unit [meters]
    • [out] ec: Error code
  • Return: Calibration result, valid when error code is not set

clearServoAlarm()

void rokae::BaseRobot::clearServoAlarm ( error_code & ec)

Clear servo alarm

  • Parameter: [out] ec: Error code, set to -1 when there is a servo alarm and clearing fails

enableCollisionDetection()

template<unsigned short DoF>
void Cobot<DoF>::enableCollisionDetection(const std::array<double, DoF> sensitivity,StopLevel behaviour,double fallback_compliance,error_code &ec)

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
      1. When the behavior after collision is safe stop or trigger pause, this parameter means the fallback distance after collision, unit: meters
      2. When the behavior after collision is compliant stop, this parameter means the compliance, range [0.0, 1.0]
    • [out] ec: Error code

disableCollisionDetection()

void BaseCobot::disableCollisionDetection(error_code &ec)

Disable collision detection function

  • Parameter: [out] ec: Error code

getSoftLimit()

template<WorkType Wt, unsigned short DoF>
bool rokae::Robot_T< Wt, DoF >::getSoftLimit ( std::array< double[2], DoF > &limits,error_code &ec )

Get current soft limit values

  • Parameters:
    • [out] limits Soft limits for each axis [lower limit, upper limit], unit: radians
    • [out] ec: Error code
  • Return: true - Enabled | false - Disabled

setSoftLimit()

template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T< Wt, DoF >::setSoftLimit ( bool enable,error_code &ec,const std::array< double[2], DoF > & limits = {{DBL_MAX, DBL_MAX}} )

Set soft limits. Soft limit setting requirements:

  1. When enabling soft limits, the robot arm should be powered off and in manual mode;
  2. Soft limits cannot exceed mechanical hard limits
  3. Current joint angles of the robot arm should be within the set limit range
  • Parameters:
    • [in] enable true - Enable | false - Disable.
    • [out] ec: Error code
    • [in] limits [lower limit, upper limit] for each axis, unit: radians.
      1. When limits is default value, it is considered as only enabling soft limits without modifying values; when not default value, modify soft limits first then enable
      2. When disabling soft limits, limit values will not be modified

queryControllerLog()

std::vector< LogInfo > rokae::BaseRobot::queryControllerLog ( unsigned count,const std::set< LogInfo::Level > & level,error_code & ec,unsigned offset = 0 )

Query latest controller logs

  • Parameters:
    • [in] count Number of logs to query, maximum is 10
    • [in] level Specify log level, empty set means no specification
    • [out] ec: Error code
    • [in] offset Offset number, for example 0 means start querying from the latest log, 10 means start from the 11th log
  • Return: Log information

recoverState()

void rokae::BaseRobot::recoverState(int item, error_code &ec)

Restore robot state according to options

  • Parameters:
    • [in] item Recovery option, 1: Emergency stop recovery
    • [out] ec: Error code

setRailParameter()

template<typename R>
void rokae::setRailParameter(const std::string &name, R value, error_code &ec)

Set guide rail parameters

  • Template parameter: Parameter type
  • Parameters:
    • [in] name: Parameter name, see value description
    • [in] value:
      Parameter:Parameter NameData Type
      Switchenablebool
      Base Coordinate SystembaseFrameFrame
      Guide Rail Namenamestd::string
      Encoder ResolutionencoderResolutionint
      Reduction RatioreductionRatiodouble
      Motor Max Speed (rpm)motorSpeedint
      Soft Limit (m), [lower, upper]softLimitstd::vector<double>
      Motion Range (m), [lower, upper]rangestd::vector<double>
      Max Speed (m/s)maxSpeeddouble
      Max Acceleration (m/s^2)maxAccdouble
      Max Jerk (m/s^3)maxJerkdouble

getMechUnit()

template<typename R>
void getMechUnit(const std::string &name, const std::string& info, R &value, error_code &ec) noexcept;

Read mechanical unit parameters

  • Template parameter: Parameter type
  • Parameters:
    • [in] name Parameter name, u1~u6
    • [in] info Parameter name, see value description
    • [in]value
      • Parameter | Parameter Name | Data Type
      • Whether mechanical unit is activated | activation | bool
      • Axis names, order same as setting order | axes_info | string array
      • Whether mechanical unit is enabled | enable | bool
      • Mechanical unit fixed name | fixed_name | string
      • Mechanical unit type | mech_link_type | int
      • Custom mechanical unit name | unit_name | string
      • 0: Base axis 1: Positioner 2: Servo gun 3: Flange additional axis
    • [out] ec: Error code, returns error code if parameter name does not exist or data type does not match

getExtAxisInfo()

 template<typename R>
void getExtAxisInfo(const std::string &name, const std::string& info, R &value, error_code &ec)

Read mechanical axis unit parameters

  • Template parameter: Parameter type

  • Parameters:

    • [in] name Parameter name, axis1~axis6

    • [in] info Parameter name, see value description

    • [in]value

      • Parameter | Parameter Name | Data Type
      • Which data in point is mapped | ext_data_number | int
      • Which driver is connected | ext_axis_number | int
      • Whether it is servo gun | is_servo_gun | bool
      • Max acceleration | max_acc | double
      • Max jerk | max_jerk | double
      • Max speed | max_speed | double
      • Soft limit lower | soft_limit_lower | double
      • Soft limit upper | soft_limit_upper | double
      • Zero value | zero_value | int
      • Motor overload coefficient | motor_overload_coefficient | int
      • Motor torque limiting | motor_torque_limiting | double
      • Reduction ratio | reduction_ratio | double
      • Motor rated torque | rated_torque_of_motor | double
      • Resolution | resolution_ratio | int
      • Joint direction | joint_orient | bool (true for positive)
      • Whether coordinate system is calibrated | coordinate_calibrated |bool
      • Driver alias/fixed name | driver_name | std::string
      • 0: Base axis 1: Positioner 2: Servo gun 3: Flange additional axis

      [out] ec Error code, returns error code if parameter name does not exist or data type does not match

getRailParameter()

template<typename R>
void rokae::getRailParameter (const std::string &name, R &value, error_code &ec)

Read guide 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

configNtp()

void rokae::BaseRobot::configNtp(const std::string &server_ip, error_code &ec)

Configure NTP. Non-standard feature, requires additional installation

  • Parameters:
    • [in] server_ip NTP server IP
    • [out] ec: Error code, NTP not properly installed, or IP address format error

syncTimeWithServer()

void rokae::BaseRobot::syncTimeWithServer(error_code &ec)

Manually synchronize time once, remote IP is configured through configNtp. Takes several seconds, blocks waiting for synchronization to complete, interface preset timeout is 12 seconds

  • Parameter: [out] ec: Error code. NTP service not properly installed, or unable to synchronize with server

sdkVersion()

static std::string rokae::BaseRobot::sdkVersion ( )

Query xCore-SDK version

  • Return: Version number

2 Motion Control (Non-real-time Mode)

setMotionControlMode()

void rokae::BaseRobot::setMotionControlMode ( MotionControlMode mode, error_code & ec )

Set motion control mode

  • Note: Before calling various motion control interfaces, the corresponding control mode must be set.
  • Parameters:
    • [in] mode: Mode
    • [out] ec: Error code

moveReset()

void rokae::BaseRobot::moveReset (error_code &ec )

Motion reset, clear sent motion commands, clear execution information

  • Note: Robot class calls motion reset once during initialization. When switching control between RL program and SDK motion commands, motion reset is required first.
  • Parameter: [out] ec Error code

stop()

void rokae::BaseRobot::stop ( error_code & ec)

Pause robot motion; after pause, can call moveStart() to continue motion. If need to completely stop and no longer execute added commands, can call moveReset()

  • Note: Currently supports stop2 stop type, planned stop without power off, see StopLevel. After calling this interface, can call moveStart() to continue motion after pause. If need to completely stop and no longer execute added commands, can call moveReset()
  • Parameter: [out] ec: Error code

moveStart()

void rokae::BaseRobot::moveStart( error_code &ec )

Start/Continue motion

  • Parameter: [out] ec: Error code

moveAppend() [1/3]

template<class Command >
void rokae::BaseRobot::moveAppend (const std::vector<Command> &cmds, std::string &cmdID,error_code &ec )

Add single or multiple motion commands, call moveStart() to start motion after adding

  • Template parameter: Command Motion command class: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand
  • Parameters:
    • [in] cmds Command list, allowed count is 1-100, must be same type of commands
    • [out] cmdID ID of this command, can be used to query command execution information
    • [out] ec Error code, only reports errors before command sending, including: 1) Network connection problem; 2) Command count does not match;

moveAppend() [2/3]

template<class Command >
void rokae::BaseRobot::moveAppend (std::initializer_list< Command > cmds, std::string &cmdID,error_code &ec )

Add single or multiple motion commands, call moveStart() to start motion after adding

  • Template parameter Command Motion command class: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand
  • Parameters:
    • [in] cmds Command list, allowed count is 1-100, must be same type of commands
    • [out] cmdID ID of this command, can be used to query command execution information
    • [out] ec Error code, only reports errors before command sending, including: 1) Network connection problem; 2) Command count does not match;

moveAppend() [3/3]

template<class Command >
void rokae::BaseRobot::moveAppend(const Command &cmds, std::string &cmdID, error_code &ec )

Add single motion command, call moveStart() to start motion after adding

  • Template parameter: Command Motion command class: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand | MoveWaitCommand
  • Parameters:
    • [in] cmds Command
    • [out] cmdID ID of this command, can be used to query command execution information
    • [out] ec Error code, only reports errors before command sending, including: 1) Network connection problem; 2) Command count does not match;

executeCommand() [1/2]

template<class Command >
void rokae::BaseRobot::executeCommand( std::initializer_list< Command > cmds,error_code & ec )

Execute single or multiple motion commands, robot starts motion immediately after calling

  • Template parameter: Command Motion command class: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand;
  • Parameters:
    • [in] cmds Command list, allowed count is 1-1000
    • [out] ec Error code, only reports errors before execution, including: 1) Network connection problem; 2) Command count does not match; 3) Robot cannot move in current state, such as not powered on

executeCommand() [2/2]

template<class Command >
void rokae::BaseRobot::executeCommand( std::vector< Command > cmds,error_code & ec )

Execute single or multiple motion commands, robot starts motion immediately after calling

  • Template parameter: Command Motion command class: MoveJCommand | MoveAbsJCommand | MoveLCommand | MoveCCommand | MoveCFCommand | MoveSPCommand;
  • Parameters:
    • [in] cmds Command list, allowed count is 1-1000
    • [out] ec Error code, only reports errors before execution, including: 1) Network connection problem; 2) Command count does not match; 3) Robot cannot move in current state, such as not powered on

setDefaultSpeed()

void rokae::BaseRobot::setDefaultSpeed ( int speed, error_code &ec )

Set default motion speed, initial value is 100

  • Note: This value represents the maximum end linear speed (unit mm/s), automatically calculates corresponding joint speed
  • Parameters:
    • [in] speed This interface does not limit parameter range. Actual effective range of end linear speed is 5-4000 (collaborative), 5-7000 (industrial). Joint speed percentage is divided into 5 ranges:
      • < 100 : 10%;
      • 100 ~ 200 : 30%;
      • 200 ~ 500 : 50%;
      • 500 ~ 800 : 80%;
      • 800 : 100%

    • [out] ec Error code

setDefaultZone()

void rokae::BaseRobot::setDefaultZone (double zone, error_code & ec )

Set default blending zone

  • Note: This value represents the maximum blending zone radius (unit: mm), automatically calculates blending percentage. If not set, it is 0 (fine, no blending zone)
  • Parameters:
    • [in] zone: This interface does not limit parameter range. Actual effective range of blending zone radius is 0-200. Blending percentage is divided into 4 ranges:
      • < 1 : 0 (fine);
      • 1 ~ 20 : 10%;
      • 20 ~ 60 : 30%;
      • 60 : 100%
    • [out] ec: Error code

setDefaultConfOpt()

void rokae::BaseRobot::setDefaultConfOpt(bool forced, error_code &ec)

Set whether to use axis configuration data (confData) to calculate inverse kinematics. Initial value is false

  • Parameters:
    • [in] forced true - Use confData in motion commands to calculate Cartesian point inverse kinematics, if calculation fails returns error; false - Do not use, inverse kinematics will select the nearest solution to current robot joint angles
    • [out] ec Error code

setAutoIgnoreZone()

void rokae::BaseRobot::setAutoIgnoreZone(bool enable, error_code &ec)

Set whether motion commands automatically cancel blending zone. Initial value is true

  • Parameters:
    • [in] enable true - Automatically cancel blending zone | false - Will not automatically cancel blending zone
    • [out] ec Error code

setMaxCacheSize()

void rokae::BaseRobot::setMaxCacheSize(int number, error_code &ec)

Set maximum cache command count, referring to the number of path points sent to controller for planning, allowed range [1,1000], initial value is 300.

  • Note: If trajectories are mostly short trajectories, can increase this value to avoid robot stopping due to untimely command sending (after stopping, if there are unexecuted commands, can moveStart() to continue;

  • Parameters:

    • [in] number: Count
    • [out] ec Error code

adjustSpeedOnline()

void rokae::BaseRobot::adjustSpeedOnline(double scale, error_code &ec)

Dynamically adjust robot motion rate, effective in non-real-time mode.

  • Parameters:
    • [in] scale: Speed ratio of motion commands, range 0.01 - 1. When scale is set to 1, robot will move at the original path speed.
    • [out] ec: Error code

getAcceleration()

void rokae::BaseRobot::getAcceleration(double &acc, double &jerk, error_code &ec)

Read current acceleration/deceleration and jerk

  • Parameters:
    • [out] acc: Percentage of system preset acceleration
    • [out] jerk: Percentage of system preset jerk
    • [out] ec: Error code

adjustAcceleration()

void rokae::BaseRobot::adjustAcceleration(double acc, double jerk, error_code &ec)

Adjust motion acceleration/deceleration and jerk. If called during robot motion, current executing command does not take effect, next command takes effect

  • Parameters:
    • [in] acc: Percentage of system preset acceleration, range [0.2, 1.5], exceeding range will not report error, automatically changed to upper or lower limit
    • [in] jerk: Percentage of system preset jerk, range [0.1, 2], exceeding range will not report error, automatically changed to upper or lower limit
    • [out] ec: Error code

setEventWatcher()

void rokae::BaseRobot::setEventWatcher(Event eventType, const EventCallback &callback, error_code &ec)

Set callback function for receiving events

  • Parameters:
    • [in] eventType: Event type
    • [in] callback: Callback function for handling events. Description:
      1. For Event::moveExecution, callback function executes in the same thread, please avoid long execution time operations in the function;
      2. Event::safety uses independent thread callback each time, no execution time limit
    • [out] ec: Error code

queryEventInfo()

EventInfo rokae::BaseRobot::queryEventInfo(Event eventType, error_code &ec)

Query event information. Same information as provided when setEventWatcher() callback, difference is this interface uses active query method

  • Parameters:
    • [in] eventType: Event type
    • [out] ec: Error code
  • Return: Event information

startJog()

void rokae::BaseRobot::startJog ( JogOpt::Space space,
double rate,
double step,
unsigned index,
bool direction,
error_code &ec )

Start jogging the robot, need to switch to manual operation mode.

  • Note: After calling this interface and robot starts moving, regardless of whether robot has stopped by itself, must call stop() to end jog operation, otherwise robot will remain in jog running state.
  • Parameters:
    • [in] space jog reference coordinate system.
      1. Tool/workpiece coordinate system usage principles same as setToolset();
      2. Industrial 6-axis models and xMateCR/SR 6-axis models support two singularity avoidance methods Jog: Space::singularityAvoidMode, Space::baseParallelMode
      3. CR5 axis models support parallel base mode Jog: Space::baseParallelMode
    • [in] rate: Rate, range 0.01 - 1
    • [in] step: Step length. Unit: Cartesian space - millimeters | Axis space - degrees. Step length greater than 0 is acceptable, no upper limit set, if robot cannot continue jogging it will stop motion by itself.
    • [in] index According to different space, this parameter means:
      1. World coordinate system, base coordinate system, flange coordinate system, tool workpiece coordinate system: a) 6-axis models: 0~5 correspond to X, Y, Z, Rx, Ry, Rz respectively. >5 represents external axis (if any) b) 7-axis models 6 represents elbow joint, >6 represents external axis (if any)
      2. Axis space: Joint index, starting from 0
      3. Singularity avoidance mode, parallel base mode: a) 6-axis models: 05 correspond to X, Y, Z, J4(4th axis), Ry, J6(6th axis) respectively; b) 5-axis models: 04 correspond to X, Y, Z, Ry, J5(5th axis) respectively
    • [in] direction According to different space and index, this parameter means:
      1. Singularity avoidance mode J4: true - ±180° | false - 0°;
      2. Parallel base mode J4 & Ry: true - ±180° | false - 0°
      3. Others, true - Positive direction | false - Negative direction
    • [out] ec Error code

startJogWithExt()

void startJogWithExt(JogOpt::Space space, double rate,double step, unsigned int index, bool direction, std::string fixed_name, error_code& ec, bool is_ext = true)

Start jogging robot + external axis, need to switch to manual operation mode.

  • Note: After calling this interface and robot starts moving, regardless of whether robot has stopped by itself, must call stop() to end jog operation, otherwise robot will remain in jog running state.

  • Parameters:

    • [in] space jog reference coordinate system.

      1. Tool/workpiece coordinate system usage principles same as setToolset();
      2. Industrial 6-axis models and xMateCR/SR 6-axis models support two singularity avoidance methods Jog: Space::singularityAvoidMode, Space::baseParallelMode
      3. CR5 axis models support parallel base mode Jog: Space::baseParallelMode
    • [in] rate: Rate, range 0.01 - 1

    • [in] step: Step length. Unit: Cartesian space - millimeters | Axis space - degrees. Step length greater than 0 is acceptable, no upper limit set, if robot cannot continue jogging it will stop motion by itself.

    • [in] index According to different space, this parameter means:

      1. World coordinate system, base coordinate system, flange coordinate system, tool workpiece coordinate system: a) 6-axis models: 0~5 correspond to X, Y, Z, Rx, Ry, Rz respectively. >5 represents external axis (if any) b) 7-axis models 6 represents elbow joint, >6 represents external axis (if any)
      2. Axis space: Joint index, starting from 0
      3. Singularity avoidance mode, parallel base mode: a) 6-axis models: 05 correspond to X, Y, Z, J4(4th axis), Ry, J6(6th axis) respectively; b) 5-axis models: 04 correspond to X, Y, Z, Ry, J5(5th axis) respectively
    • [in] direction According to different space and index, this parameter means:

      1. Singularity avoidance mode J4: true - ±180° | false - 0°;
      2. Parallel base mode J4 & Ry: true - ±180° | false - 0°
      3. Others, true - Positive direction | false - Negative direction
    • fixed_name fixed_name works with index, if fixed_name passes any character, is_ext is false, index is 0, then jog robot's first axis

      If fixed_name passes u1, index is 0, then jog mechanical unit u1's first axis

    • is_ext: Whether it is a moving external axis

    • [out] ec Error code

setAvoidSingularity()

void rokae::xMateRobot::setAvoidSingularity (AvoidSingularityMethod method, bool enable,double limit, error_code &ec )
void rokae::StandardRobot::setAvoidSingularity (AvoidSingularityMethod method, bool enable,double limit, error_code &ec )

Enable/Disable singularity avoidance function. Only applicable to some models:

  1. Four-axis lock: Supports industrial 6-axis, xMateCR and xMateSR 6-axis models;
  2. Posture sacrifice: Supports all 6-axis models;
  3. Axis space interpolation: Supports industrial 6-axis models
  • Parameters:
    • [in] method: Singularity avoidance method
    • [in] enable: true - Enable function | false - Disable. For four-axis lock method, ensure 4th axis is at zero position before enabling.
    • [in] limit: For different avoidance methods, this parameter means:
      1. Posture sacrifice: Allowed posture error, range (0, PI*2], unit radians
      2. Axis space interpolation: Avoidance radius, range [0.005, 10], unit meters
      3. Four-axis lock: No parameter
    • [out] ec: Error code

getAvoidSingularity()

bool rokae::xMateRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
bool rokae::StandardRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)

Query whether in singularity avoidance state

  • Parameters:
    • [in] method: Singularity avoidance method
    • [out] ec: Error code
  • Return: true - Enabled | false – Disabled

getAvoidSingularity()

bool rokae::xMateRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)
bool rokae::StandardRobot::getAvoidSingularity (AvoidSingularityMethod method, error_code &ec)

Query whether in singularity avoidance state

  • Parameters:
    • [in] method: Singularity avoidance method
    • [out] ec: Error code
  • Return: true - Enabled | false – Disabled

checkPath() [1/3]

std::vector<double> rokae::BaseRobot::checkPath(const CartesianPosition &start,
const std::vector<double> &start_joint, const CartesianPosition &target, error_code &ec)

Check if Cartesian trajectory is reachable, straight line trajectory. Supports guide rail, returned target joint angle is number of axes + number of external axes

  • Parameters:
    • [in] start: Start point
    • [in] start_joint: Start joint angles [radians]
    • [in] target: Target point
    • [out] ec: Error code
  • Return: Calculated target joint angles, only valid when no error code

checkPath() [2/3]

int rokae::BaseRobot::checkPath(const std::vector<double> &start_joint,
const std::vector<CartesianPosition> &points,
std::vector<double> &target_joint_calculated,
error_code &ec)

Check multiple straight line trajectories

  • Parameters:
    • [in] start_joint: Start joint angles, unit [radians]
    • [in] points: Cartesian points, at least 2 points required, first point is start point
    • [out] target_joint_calculated: If check passes. Returns calculated target joint angles
    • [out] ec: Reason for check failure
  • Return: If check fails, returns index of error target point in points. Other cases return 0

checkPath() [3/3]

std::vector<double> rokae::BaseRobot::checkPath(const CartesianPosition &start,
const std::vector<double> &start_joint,
const CartesianPosition &aux,
const CartesianPosition &target,
error_code &ec, double angle =0.0,
MoveCFCommand::RotType rot_type = MoveCFCommand::constPose)

Check if Cartesian trajectory is reachable, including arc, full circle. Supports guide rail, returned target joint angle is number of axes + number of external axes

  • Parameters:
    • [in] start: Start point
    • [in] start_joint: Start joint angles [radians]
    • [in] aux: Auxiliary point
    • [in] target: Target point
    • [out] ec: Error code
    • [in] angle: Full circle execution angle, when not equal to zero means checking full circle trajectory
    • [in] rot_type: Full circle rotation type
  • Return: Calculated target joint angles, only valid when no error code

setTeachPendantMode()

void setTeachPendantMode(bool enable, error_code& ec)

Teach pendant hot swap. Note: Only some models support teach pendant hot swap, unsupported models will return error code. After not using teach pendant, enable button and emergency stop button will be disabled

  • Parameters:
    • [in] enable true - Use teach pendant | false - Do not use teach pendant
    • [out] ec: Error code

3 Real-time Motion Control

getRtMotionController()

template <unsigned short DoF>
std::weak_ptr<RtMotionControlCobot<DoF>> Cobot<DoF>::getRtMotionController ()
std::weak_ptr<RtMotionControlIndustrial<6>> StandardRobot::getRtMotionController()

Create real-time motion control class instance, perform real-time mode related operations through this instance pointer.

  • Note: Unless this interface is called repeatedly, client internal logic will not actively destruct returned objects, including but not limited to disconnecting from robot connection disconnectFromRobot(), switching to non-real-time motion control mode, etc., but performing above operations then conducting real-time mode control will cause exceptions.

  • Return: Controller object

  • Exceptions:

    • RealtimeControlException: Failed to create RtMotionControl instance due to network issues
    • ExecutionException Not switched to real-time motion control mode

reconnectNetwork()

void rokae::MotionControl< MotionControlMode::RtCommand >::reconnectNetwork ( error_code & ec )

Reconnect to real-time control server

  • Parameter: [out] ec: Error code

disconnectNetwork()

void rokae::MotionControl< MotionControlMode::RtCommand >::disconnectNetwork ()

Disconnect from real-time control server, close data receiving and command sending ports. But will not disconnect from robot. If robot is in motion, will stop motion immediately after disconnection.

setControlLoop()

template<class Command>
void rokae::MotionControl< MotionControlMode::RtCommand >::setControlLoop (const std::function<Command(void)>& callback, int priority = 0, bool useStateDataInLoop = false )

Use periodic scheduling, set callback function.

  • Note:
    1. Callback function should plan motion commands in 1 millisecond cycle, planning result is function return value. SDK filters the return value and sends to controller.
    2. JointPosition joint angle array length, and Torque joint torque value array length should be same as robot axis number. If different, no error will be reported, but may cause unreasonable commands
    3. When a motion loop ends, can be identified by returning Command.setFinish(), SDK internally will stop motion and stop calling callback function
  • Template parameter: JointPosition | CartesianPosition | Torque
  • Parameters:
    • [in] callback: Callback function. According to different control modes (RtControllerMode), function return value has 3 types: joint angle/Cartesian pose/torque. Where Cartesian pose uses rotation matrix to represent rotation, pos is end effector pose relative to base coordinate system.
    • [in] priority: Task priority, 0 means not specified. This parameter only takes effect when using real-time operating system, if cannot set will print console error message.
    • [in] useStateDataInLoop: Whether need to read state data within the cycle. When set to true:
      1. xCore-SDK will update real-time state data updateStateData() before callback function, directly getStateData() in callback function;
      2. State data sending period should be consistent with control period, 1ms: startReceiveRobotState(interval = milliseconds(1));

startLoop()

void rokae::MotionControl< MotionControlMode::RtCommand >::startLoop (bool blocking = true )

Start periodic execution of scheduling tasks.

  • Parameter: [in] blocking: Whether to block the thread calling this function. If non-blocking thread, need to call stopLoop() to stop scheduling task, otherwise cannot start next loop cycle.

  • Exception: RealtimeControlException: Command sending network exception; or command type does not match control mode; or error occurred when controller executed sent command

stopLoop()

void rokae::MotionControl< MotionControlMode::RtCommand >::stopLoop ()

Stop periodic execution of scheduling tasks.

  • Exception: RealtimeControlException: Exception occurred during execution

startMove()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::startMove ( RtControllerMode rtMode )

Specify control mode, robot prepares to start motion, this interface needs to be called before each callback execution. Calling this interface will not immediately start robot motion, but will start after motion commands are sent.

  • Note:
    1. Before startMove, parameters should be set in sequence, such as filtering impedance parameters, etc., then call startMove() after setting is complete. Executing other commands after calling startMove may fail, such as power off operations. Correct stop method is to call stopMove;
    2. If not set to receive state data through startReceiveRobotState(), this function will automatically set it when called
  • Parameter: [in] rtMode: Control mode
  • Exceptions:
    • RealtimeStateException: Repeatedly called after motion has started
    • RealtimeParameterException: Specified unsupported control mode
    • RealtimeControlException: Controller cannot switch to this control mode, often occurs when switching to force control mode

stopMove()

void rokae::MotionControl< MotionControlMode::RtCommand >::stopMove ()

Robot stops motion, stops receiving motion commands sent by client.

  • Note: In addition, JointPosition/CartesianPosition/Torque commands can identify the end of a motion loop through setFinished(), after identification robot will stop motion, presenting the same effect as calling stopMove(). This function is only for real-time control, cannot be used to stop non-real-time motion commands.

sendCommand()

template<class Command>
void sendCommand(const Command &cmd);

Send JointPosition/CartesianPosition/Torque commands. Suitable for not using scheduling period, program directly sends commands

  • Note:

    • After starting motion, continuously call this function to send motion commands. Since controller execution command period is 1ms, command sending interval also needs to be controlled at 1ms
    • If sending interval is too long, it will be judged as communication packet loss; if too short, it will cause servo error.
    • If sending interval is too long, it will be judged as communication packet loss; if too short, it will cause servo error.
    • Directly sending commands means no need for scheduling period, setControlLoop(), startLoop(), stopLoop() and other related functions are not needed
  • Parameters

    • [in] cmd According to different control modes (RtControllerMode), there are 3 motion commands: joint angle/Cartesian pose/torque
  • Exceptions

    • ArgumentException Command value contains illegal values
    • RealtimeStateException Motion not started
    • RealtimeControlException Command sending network exception; or command type does not match control mode; or error occurred when controller executed sent command

startReceiveRobotState()

template<WorkType Wt, unsigned short DoF>
void rokae::Robot_T::startReceiveRobotState (std::chrono::steady_clock::duration interval, const std::vector<std::string>& fields)

Let robot start sending real-time state data. Block waiting to receive first frame message, timeout is 3 seconds

  • Parameters:
    • [in] interval: Controller sending state data interval, allowed duration: 1ms/2ms/4ms/8ms/1s
    • [in] fields Robot state data to receive, maximum total length is 1024 bytes. Supported data and names see data_types.h, RtSupportedFields
  • Exceptions:
    • RealtimeControlException: Set unsupported state data; or robot cannot start sending data; or total length exceeds 1024
    • RealtimeStateException Already started sending data; or timeout without receiving first frame data

stopReceiveRobotState()

void rokae::BaseRobot::stopReceiveRobotState ()

Stop receiving real-time state data, controller stops sending at the same time. Can be used to reset state data to receive.

updateRobotState()

unsigned rokae::BaseRobot::updateRobotState(std::chrono::steady_clock::duration timeout)

Receive robot state data once. Need to call this function before reading data each cycle; recommended to call according to set sending frequency to get latest data

  • Parameter: [in] timeout: Timeout time
  • Return: Received data length. If no data received before timeout, returns 0.
  • Exceptions:
    • RealtimeControlException: Cannot receive data; or received data has errors causing inability to parse
    • RealtimeMotionException Real-time mode motion error

getStateData()

template<typename R >
int rokae::BaseRobot::getStateData ( const std::string &fieldName,R & data )

Read robot state data

  • Note: Note that the passed data type should be consistent with the data type.
  • Template parameter: R Data type
  • Parameters:
    • [in] fieldName: Data name
    • [out] data: Value
  • Return: If no such data name; or not set to receive through startReceiveRobotState(); or data type does not match R, returns -1. Successfully read returns 0.
  • Exception: RealtimeStateException: Network error

setServoJoint()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setServoJoint(double ServoJ_T, double ServoJ_Lookahead, double ServoJ_Kp, error_code &ec) noexcept;

Send joint position through real-time mode sendCommand, open calling period, gain and lookahead time settings, and enable servoJ function

  • Parameters:
    • [in] ServoJ_T Period for calling servoJ when sending joint position, unit s
    • [in] ServoJ_Lookahead Lookahead time, limit on motion speed after sending joint position, unit s
    • [in] ServoJ_Kp Control gain
    • [out] ec Error code
  • Return: None

stopServoJoint()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::stopServoJoint() noexcept;

Disable servoJ function, need to close when stopping using setServoJoint

hasMotionError()

template <WorkType Wt, unsigned short DoF>
bool RtMotionControl<Wt, DoF>::hasMotionError() noexcept;

Whether real-time mode motion has occurred motion error

  • Return: true - Has error.

MoveJ()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveJ( double speed,
const std::array< double, DoF > & start,
const std::array< double, DoF > & target )

MoveJ command, host plans path, blocks until reaching target. If error occurs during motion, will stop blocking state and return.

  • Description

  • Not recommended for use, please use non-real-time mode command MoveAbsJCommand.

  • Parameters:

    • [in] speed: Speed ratio coefficient
    • [in] start: Start joint angles, need to be current robot joint angles, otherwise may cause power off.
    • [in] target: Robot target joint angles
  • Exception: RealtimeMotionException: Error occurred during robot motion

moveL()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveL ( double speed,
CartesianPosition & start,
CartesianPosition & target )

MoveL command, host plans path, blocks until reaching target. If error occurs during motion, will stop blocking state and return.

  • Description

  • Not recommended for use, please use non-real-time mode command MoveLCommand.

  • Parameters:

    • [in] speed: Speed ratio coefficient, range 0 - 1
    • [in] start: Start pose, need to be current robot pose, otherwise may cause power off. If TCP is set, it should be tool pose relative to base coordinate system.
    • [in] target: Robot target pose. Similarly if TCP is set, it should be TCP pose relative to base coordinate system
  • Exceptions:

    • RealtimeParameterException: Start or target pose parameter error
    • RealtimeMotionException: Error occurred during robot motion

MoveC()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::MoveC ( double speed,
CartesianPosition & start,
CartesianPosition & aux,
CartesianPosition & target )

MoveC command, blocks until reaching target. If error occurs during motion, will stop blocking state and return.

  • Description

  • Not recommended for use, please use non-real-time mode command MoveCCommand.

  • Parameters:

    • [in] speed: Speed ratio coefficient
    • [in] start Robot start pose, need to be current robot pose. If TCP is set, it should be tool pose relative to base coordinate system.
    • [in] aux: Robot auxiliary point pose. Similarly if TCP is set, it should be TCP pose relative to base coordinate system
    • [in] target: Robot target pose. Similarly if TCP is set, it should be TCP pose relative to base coordinate system
  • Exceptions:

    • RealtimeParameterException: Point error, cannot calculate arc path
    • RealtimeMotionException: Error occurred during robot motion

getRobotCfg_DHparam()

std::vector<double> getRobotCfg_DHparam(bool get_nominal, error_code &ec)

Read DH parameters

  • Parameters:
    • [in] get_nominal false - Optimized or set parameters | true - Read nominal parameters. Generally recommended to use false
    • [out] ec Error code
  • Return: DH parameters - valid when error code is 0. In order: Alpha[°], A[mm], D[mm], Theta[°] for each axis

setFilterLimit()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setFilterLimit( bool limit_rate,double cutoff_frequency )

Set amplitude limit filter parameters.

  • Parameters:
    • [in] limit_rate: true - Amplitude limit enabled
    • [in] cutoff_frequency: Cutoff frequency. Range is 0 ~ 1000Hz, recommended 10~100Hz.
  • Return: true - Setting successful

setCartesianLimit()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setCartesianLimit ( const std::array< double, 3 > & lengths,const std::array< double, 16 > & frame,error_code & ec )

Set Cartesian space motion area, motion will stop if exceeding set area. Not force control virtual wall. If robot end or TCP end exceeds safety area, motor will also be powered off.

  • Parameters:
    • [in] lengths: Safety area cuboid length, width, height, corresponding to XYZ, unit: meters
    • [in] frame: Safety area cuboid center pose relative to base coordinate system
    • [out] ec: Error code

setJointImpedance()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setJointImpedance ( const std::array< double, DoF > & factor,error_code & ec )

Set axis space impedance control coefficient, effective during axis space impedance motion

  • Parameters:
    • [in] factor: Axis space impedance coefficient, unit: Nm/rad.
      • xMateErPro model maximum stiffness is 300
      • Other models maximum stiffness is 300 Actual effective maximum value is related to hardware status such as sensors, if vibration occurs, please try to reduce impedance coefficient.
    • [out] ec: Error code

setCartesianImpedance()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCartesianImpedance ( const std::array< double, 6 > & factor,error_code & ec )

Set Cartesian space impedance control coefficient, effective during Cartesian impedance motion

  • Parameters:
    • [in] factor: Cartesian space impedance control coefficient, maximum value is 300, unit: N/m, Nm/rad
    • [out] ec: Error code

setCollisionBehaviour()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCollisionBehaviour ( const std::array< double, DoF > & torqueThresholds,error_code & ec )

Set collision detection threshold. Collision detection only takes effect during position control, not during force control. If collision is detected, controller will send power off command, motor brake engages and disables.

  • Parameters:
    • [in] torqueThresholds: Joint collision detection threshold.
      • xMateErPro model maximum value is 20,
      • Other models maximum value is 20
      • 5-axis model maximum value is 20
    • [out] ec Error code

setEndEffectorFrame()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setEndEffectorFrame ( const std::array< double, 16 > & frame,error_code & ec )

Set end effector pose relative to robot flange, after setting TCP, controller will save configuration, robot restores default settings after restart.

  • Parameters:
    • [in] frame: End effector coordinate system homogeneous matrix relative to flange coordinate system, unit: rad, m
    • [out] ec: Error code

setLoad()

template <WorkType Wt, unsigned short DoF>
void RtMotionControl<Wt, DoF>::setLoad ( const Load & load,error_code & ec )

Set tool and load mass, center of mass and inertia matrix. After setting load, controller will save load configuration, robot restores default settings after restart.

  • Parameters:
    • [in] load: Load information
    • [out] ec: Error code

setFilterFrequency()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setFilterFrequency ( double jointFrequency,double cartesianFrequency,double torqueFrequency,error_code & ec )

Set robot controller filter cutoff frequency, used to smooth commands. Allowed range: 1 ~ 1000Hz, recommended setting is 10 ~ 100Hz.

  • Parameters:
    • [in] jointFrequency: Joint position filter cutoff frequency, unit: Hz
    • [in] cartesianFrequency: Cartesian space position filter cutoff frequency, unit: Hz
    • [in] torqueFrequency: Joint torque filter cutoff frequency, unit: Hz
    • [out] ec: Error code

setCartesianImpedanceDesiredTorque()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setCartesianImpedanceDesiredTorque ( const std::array< double, 6 > & torque,error_code & ec )

Set end desired force, effective during Cartesian space impedance motion

  • Parameters:
    • [in] torque: Cartesian space end desired force, allowed range is 30, unit: N, N·m
    • [out] ec: Error code

setTorqueFilterCutOffFrequency()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setTorqueFilterCutOffFrequency ( double frequency,error_code & ec )

Set filter parameters

  • Parameters:
    • [in] frequency: Allowed range 1 ~ 1000Hz
    • [out] ec: Error code

setFcCoor()

template <unsigned short DoF>
void RtMotionControlCobot<DoF>::setFcCoor ( const std::array< double, 16 > & frame,FrameType type,error_code & ec )

Set robot force control coordinate system

  • Parameters:
    • [in] frame: Force control coordinate system transformation matrix relative to flange coordinate system
    • [in] type: Category, specify which coordinate system is the force control task coordinate system, supports:
      1. World coordinate system FrameType::world;
      2. Tool coordinate system FrameType::tool;
      3. Path coordinate system FrameType::path (force control task coordinate system needs to track trajectory changes)
    • [out] ec: Error code

automaticErrorRecovery()

void rokae::MotionControl< MotionControlMode::RtCommand >::automaticErrorRecovery ( error_code & ec )

Automatically recover robot when error occurs.

  • Parameter: [out] ec: Error code

setRtNetworkTolerance()

void rokae::BaseCobot::setRtNetworkTolerance ( unsigned percent,error_code & ec )

Set real-time motion command sending network delay threshold, i.e., "packet loss threshold" in RobotAssist - RCI settings interface. Please set before switching to RtCommand mode, otherwise it will not take effect.

  • Parameters:
    • [in] percent: Allowed range 0 - 100, recommended 20% or above when running under Linux; recommended 60% or above when running under Windows
    • [out] ec: Error code

useRciClient()

void rokae::BaseCobot::useRciClient ( bool use, error_code & ec )

Interface compatible with RCI client settings. After setting motion control mode to real-time mode through SDK, original RCI client can no longer control robot. If there is a need to use the original version, can call this interface after switching to non-real-time mode. Then open RCI function on RobotAssist, and you can use RCI client.

  • Parameters:
    • [in] use: true - Switch to use first generation
    • [out] ec: Error code