Skip to main content

JAKA TCP/IP Control Protocol

JAKAAbout 44 min

JAKA TCP/IP Control Protocol

About the Document

JAKA supports an external control protocol based on TCP/IP. This protocol provides a rich set of interfaces, allowing customers to control the robot and retrieve information.

It is also one of the core communication protocols of the JAKA SDK.

Versions Notification

JAKA TCP/IP control protocol is primarily designed for the 1.7.2 and 1.7.1 controller versions. Some interfaces may be incompatible with these two versions, but they have been marked.

Framework

JAKA TCP/IP Control Protocol Framework

The framework is as the image below:

A TCP server runs on the robot controller to receive user-defined commands and feedback status data. The server communicates with external clients using ports 10000 and 10001, as follows:

  • Port 10001 — Used to send control commands to the robot and receive responses from the controller.
  • Port 10000 — Used to receive data returned by the robot (the user can define the transmission frequency and data content).

Users can perform further development on the robot based on the JAKA TCP/IP protocol. Please note:

  • TCP/IP commands are executed asynchronously. The returned information only indicates that the controller has received the command and completed preprocessing and forwarding. It does not reflect the final execution result of the command. Some command results require actively querying the feedback data.
  • Users need to implement the corresponding TCP client calls according to this protocol, which means users must design their own upper-level planner to send robot data (e.g., servo_j, servo_p).
  • This functionality can be used simultaneously with the JAKA App without the need to disconnect the app from the controller. However, users must ensure that only one client is connected to port 10001 at a time. Otherwise, the latter client may immediately replace the former one.

Communication Port Data Description

Data sent from port 10001 and received from port 10000 are both defined in JSON format. Users can quickly construct commands or parse feedback data based on the protocol.

Port 10001 Description

All the commands in this manual fall under this category. All robot control commands are based on port 10001. The data format for port interaction is defined as follows:

  • Message send format:
{"cmdName":"cmd","parameter1":"parameter1","parameter2":"parameter2",...}
  • Message received format:
{"cmdName":"cmd","errorCode":"0","errorMsg":"","parameter1":"parameter1","parameter2":"parameter2",...}

Port 10000 Description

Port 10000 will return robot-related data in the form of a string. The returned content can be referenced in the following example:

Example:

{
    "len":3547,
    "drag_status":false,
    "extio":Object{...},
    "errcode":"0x0",
    "errmsg":"",
    "monitor_data":Array[6],
    "torqsensor":Array[2],
    "joint_actual_position":Array[6],
    "actual_position":Array[6],
    "din":Array[144],
    "dout":Array[144],
    "ain":Array[66],
    "aout":Array[66],
    "tio_din":Array[8],
    "tio_dout":Array[8],
    "tio_ain":Array[1],
    "task_state":4,
    "homed":Array[9],
    "task_mode":1,
    "interp_state":0,
    "enabled":true,
    "paused":false,
    "rapidrate":1,
    "current_tool_id":0,
    "current_user_id":0,
    "on_soft_limit":1,
    "emergency_stop":0,
    "drag_near_limit":Array[6],
    "funcdi":Array[15],
    "powered_on":1,
    "inpos":true,
    "motion_mode":1,
    "curr_tcp_trans_vel":0,
    "protective_stop":0,
    "point_key":0,
    "netState":1
}

Notes:

  • len: the length of the data packet, generally the maximum length does not exceed 5000 bytes.*

  • drag_status: Boolean value to indicate whether it is in the drag mode.*

  • extio: the configuration and status of the extended IO modules, with internal data structure as below.

    • *status: status of all extended IO pins, including DI, DO, AI, AO.

      • status[0] the status of all extended DIs,
      • status[1] the status of all extended DOs,
      • status[2] the status of all extended AIs,
      • status[3] the status of all extended AOs.
    • setup: array of all extended IO configurations, 8 maximum. For each extended IO module, the setup follows the structure below.

      • setup[N][0]: communication type, 0:Modbus RTU, 1:Modbus TCP/IP.
        • For Modbus RTU (setup[N][0] == 0):
          • setup[N][2][0]: bard rate
          • setup[N][2][1]: data bits length
          • setup[N][2][2]: slave ID
          • setup[N][2][3]: data bits
          • setup[N][2][4]: parity check bit
          • setup[N][2][5]: stop bits length
        • For Modbus TCP (setup[N][0] == 1) :
          • setup[N][2][0]: IP address
          • setup[N][2][1]: port
          • setup[N][2][2]: slave ID.
      • setup[N][1]: the alias name of the extended IO module.
      • setup[N][2]: communication configuration, which varies as per communication type.
    • setup[N][3]: pin configuration

      • setup[N][3][0][0]: starting offset of the register in DI
      • setup[N][3][0][1]: number of DI
      • setup[N][3][1][0]: starting offset of the register in DO
      • setup[N][3][1][1]: number of DO
      • setup[N][3][2][0]: starting offset of the register in AI
      • setup[N][3][2][1]: number of AI
      • setup[N][3][3][0]: starting offset of the register in AO
      • setup[N][3][3][1]: number of AO
    • num: the number of extended IO module

    • pinmap: array of the pin map of the extended IO module

      • pinmap[N][0]: starting offset of the register in DI for setup[N]
      • pinmap[N][1]: starting offset of the register in DO of setup[N]
      • pinmap[N][2]: starting offset of the register in AI of setup[N]
      • pinmap[N][2]: starting offset of the register in AO of setup[N]
    • mode: status of the extended IO module, 0 for status on and 1 for off.

  • errcode: error code of from controller in hex string, like "0x0".

  • errmsg: error message string from controller corresponding to the errcode.

  • monitor_data: monitoring data of robot and cabinet for diagnosis.

    • monitor_data[0]: SCB major version number
    • monitor_data[1]: SCB minor version number
    • monitor_data[2]: Control cabinet temperature
    • monitor_data[3]: Control cabinet bus average power
    • monitor_data[4]: Control cabinet bus average current
    • monitor_data[5]: Monitoring data of joint axes 1-6 of the robot in array
      • monitor_data[5][0]: instantaneous current of the robot axis,
      • monitor_data[5][1]: instantaneous voltage of the robot axis,
      • monitor_data[5][2]: instantaneous temperature of the robot axis,
      • monitor_data[5][3]: instant average power,
      • monitor_data[5][4]: current fluctuation,
      • monitor_data[5][5]: cumulative running circles,
      • monitor_data[5][6]: cumulative running time,
      • monitor_data[5][7]: running circles after this boot,
      • monitor_data[5][8]: running time after this boot,
      • monitor_data[5][9]: joint torque
  • torqsensor: array of the end force sensor setup and status, with the data structure below.

    • torqsensor[0]: setup of current sensor
      • torqsensor[0][0]: communication type, 0 for network port/USB communication, 1 for TIO communication;
      • torqsensor[0][1]: communication configuration of the sensor. For communication with port address, it will be [IP, port], for communication with TIO, it will be [baudrate, databits, stopbits, parity].
      • torqsensor[0][2]: the payload and center of mass of the sensor's end.
    • torqsensor[1]: status of the sensor
      • torqsensor[1][0]: sensor status, 1 for working, 0 for off.
      • torqsensor[1][1]: sensor error code.
      • torqsensor[1][2]: sensor actual contact force (6 dimensions. Varying with the zero calibration on the app. The data might be unstable, and incompatibility might happen. Therefore not recommended for use).
      • torqsensor[1][3]: sensor original reading value (6 dimensions).
      • torqsensor[1][4]: sensor original reading value (6 dimensions, the value after compensating the payload gravity and sensor's zero point).
  • joint_actual_position: actual position of all 6 joints.

  • actual_position: actual position of the robot TCP in Cartesian space.

  • din: array of the status of all the digital inputs in cabinet.

  • dout: array of the status of all the digital outputs in cabinet.

  • ain: array of the status of all the analog inputs in cabinet.

  • aout: array of the value of all the analog outputs in cabinet.

  • tio_din: array of the status of all the tool digital inputs.

  • tio_dout: array of the status of all the tool digital outputs.

  • tio_ain: array of the status of all the tool analog inputs.

  • task_state: indicator of the power status and enabling status, 1: the robot is powered off, 2: the robot is powered on, 3: the robot is enabled, 4: the robot is enabled.

  • homed: home status of each joint (obsolete).

  • task_mode: task mode of the robot. 1: manual mode, 2: automatic mode, 3: reserved, 4: drag mode.

  • interp_state: program status, 0: idle, 1: loading, 2: paused, 3: running.

  • enabled: Boolean value to show robot enabling status.

  • paused: Boolean value to show program pausing status.

  • rapidrate: the scale rate of the robot movement.

  • current_tool_id: index of current TCP.

  • current_user_id: index of current user coordinate frame.

  • on_soft_limit: Boolean status to show whether it is on the soft limit now.

  • emergency_stop: status of the emergency stop in system, 0 for estop reset, 1 for estop triggered.

  • drag_near_limit: status to show whether it is dragged to the limit position, 0 is no, 1 is yes.

  • funcdi: setup array of the function DIs. For each function DI, the setup will be in format [diType, diIndex]. For diType, 0 indicates the cabinet DI, 1 indicates the Tool DI and 2 indicates the extended DI.

    • funcdi[0]: function DI setup to start the program.
    • funcdi[1]: function DI setup to pause the program.
    • funcdi[2]: function DI setup to continue the program.
    • funcdi[3]: function DI setup to stop the program.
    • funcdi[4]: function DI setup to power on the robot.
    • funcdi[5]: function DI setup to power off the robot.
    • funcdi[6]: function DI setup to enable robot.
    • funcdi[7]: function DI setup to disable robot.
    • funcdi[8]: function DI setup to level-1 reduction mode.
    • funcdi[9]: function DI setup to trigger protective stop.
    • funcdi[10]: function DI setup to return to safety position.
    • funcdi[11]: function DI setup to level-2 reduction mode.
    • funcdi[12]: function DI setup to clear error code.
    • funcdi[13]: function DI setup to enter drag mode.
    • funcdi[14]: function DI setup to exit drag mode.
  • powered_on: power status of the robot, 0 for powered-off, 1 for powered-on.

  • inpos: indicator to show whether it’s in position. True for robot is still, false for in movement.

  • motion_mode: motion mode (obsolete).

  • curr_tcp_trans_vel: the current movement speed at the end of current TCP.

  • protective_stop: protective stop status, 0 for normal and 1 protective stopped.

  • point_key: status to indicate whether the point button at the end of the robot is pushed down, 0 for button pushed down, and non-zero for otherwise.

  • netState: socket connection state (obsolete).

Configure optionalInfoConfig.ini

By default, the robot controller's port 10000 returns all defined data fields. Sending this data over TCP consumes a large amount of bandwidth and can affect the timeliness of data reception on the client side.

However, in actual user applications, not all data fields are used. Therefore, this version introduces a feature allowing users to configure the data fields returned by port 10000.

The controller's internal configuration file optionalInfoConfig.ini defines the data fields that users can enable or disable. When the value of a data field is set to 1, port 10000 will return that data field; when the value is set to 0, it will not be returned.

Users can set and query the status of these fields (enable or disable) through specific commands sent to port 10001.

The detailed contents of the configuration file are as follows:

[ATTROPTIONALDATA]
joint_actual_position = 1
joint_position = 1
actual_position = 1
position = 1
din = 1
dout = 1
ain = 1
aout = 1
tio_key = 1
tio_din = 1
tio_dout = 1
tio_ain = 1
relay_io = 1
mb_slave_din = 1
mb_slave_dout = 1
mb_slave_ain = 1
mb_slave_aout = 1
pn_dev_din = 1
pn_dev_dout = 1
pn_dev_ain = 1
pn_dev_aout = 1
eip_adpt_din = 1
eip_adpt_dout = 1
eip_adpt_ain = 1
eip_adpt_aout = 1
task_state = 1
homed = 1
task_mode = 1
interp_state = 1
enabled = 1
paused = 1
rapidrate = 1
current_tool_id = 1
current_user_id = 1
on_soft_limit = 1
emergency_stop = 1
drag_near_limit = 1
funcdi = 1
powered_on = 1
inpos = 1
motion_mode = 1
curr_tcp_trans_vel = 1
protective_stop = 1
point_key = 1
motion_line = 1
err_add_line = 1

[STATOPTIONALDATA]
drag_status = 1
num = 1
setup = 1
pinmap = 1
mode = 1
status = 1
extio = 1
errcode = 1
errmsg = 1
monitor_data = 1
torqsensor = 1

[PORTCONFIG]
port10000_delay_ms = 2000
  • For data in ATTROPTIONALDATA and STATOPTIONALDATA , When the value of a data is set to 0, port 10000 will not send this data; when the value is set to 1, it will send this data.

Please note:

The data obtained by the user from port 10000 is not real-time; the actual transmission cycle may be affected by network fluctuations and other factors.

Additionally, excessively large data or too fast a transmission cycle can likely cause network congestion, packet merging, and other issues (especially during network fluctuations), leading to failures in data reception or parsing on the client side.

Please try to exclude unnecessary data and set a reasonable transmission cycle.

About the Robot Orientation

In JAKA TCP/IP control protocol, the robot's spatial orientation is represented using RPY (Roll, Pitch, Yaw) angles.

In the RPY convention, the rotation transformation sequence is performed in the order of rotation around the fixed coordinate system's axes x-y-z. The rotation around the fixed coordinate system's z-axis (Rz) is called Roll; the rotation around the fixed coordinate system's y-axis (Ry) is called Pitch; and the rotation around the fixed coordinate system's x-axis (Rx) is called Yaw.

The robot's pose data format is defined as [X, Y, Z, Rx, Ry, Rz], where X, Y, and Z represent the position along the three coordinate axes (in millimeters); Rx, Ry, and Rz represent the robot's orientation, corresponding to the RPY components: Yaw, Pitch, and Roll, with units in degrees (°).

For the conversion relationship between RPY and the rotation matrix, assuming we select a fixed coordinate system {A}, the conversion from the RPY representation of a coordinate system {B} to the corresponding rotation matrix is as follows:

User Precautions

Error Code Explanation

  • When the interface returns correctly, the errorCode should be 0 (it could be either an integer or a string), not Empty or Null. If the errorCode is any value other than 0, it indicates an execution error.
  • In case of an error, the client can check the errorCode and msg in the feedback JSON data:
    • When the errorCode is 0, the errorMsg will be empty, indicating successful execution.
    • When the errorCode is any other value, the errorMsg will contain specific error information, indicating that an exception occurred in the program.

Error Code Short Lists

Basic Robot Operations (200-249)

ERROR_INSTALLATION_ANGLE_OUT_OF_RANGE="0x000200" #installation angle out of range

Move Commands (250-349)

ERROR_SETTING_MOTION_PLANNER="0x000250"

ERROR_NOT_IN_SERVO_MODE="0x000350" #try to servo when not in servo mode ERROR_SET_FILTER_IN_SERVO_MODE = "0x000351" #cannot set servo filter when in servo mode ERROR_SERVO_PARAMETER_INVALID = "0x000352" #servo params invalid ERROR_SERVO_FILTER_INVALID = "0x000353" #servo filter params invalid

ERROR_IO_INDEX_OUT_OF_RANGE = "0x000400" #IO index out of range ERROR_IO_TYPE_OUT_OF_RANGE = "0x000401" #IO type out of range

ERROR_VAR_ALIAS_EXIST = "0x000450" #var alias already exist ERROR_VAR_ID_NOT_EXIST = "0x000451" #var id not exist

ERROR_COLLISION_LEVEL_OUT_OF_RANGE = "0x000500" #collision level out of range

ERROR_FAIL_KINE_INVERSE = "0x000550" #kine_inverse fail

Drag and force control
FTP part
TIO part
Reserved for future features

Other Notifications

  • The errorCode can be either a string or an integer.
  • All commands are non-blocking commands.
  • The units used in the protocol are: mm (millimeters) and deg (degrees).
  • TCP IO indexes start from 1, while SDK IO indexes start from 0.

Port 10000 and 10004 Settings

Port 10004 is a dedicated SDK port, and the returned data is the same as that of port 10000.

Get the Transmission Cycle of Port 10000

Send message:

{"cmdName":"get_port10000_delay_ms"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_port10000_delay_ms", "port10000_delay_ms": 2000}

Modify the Transmission Cycle of Port 10000

Send message:

{"cmdName":"set_port10000_delay_ms","port10000_delay_ms":20}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_port10000_delay_ms"}

Query the Configuration of optionalInfoConfig

Send message:

{"cmdName":"getOptionalInfoConfig","section":"PORTCONFIG","key":"port10000_delay_ms"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "getOptionalInfoConfig", "value": 20}

Send message:

{"cmdName":"getOptionalInfoConfig","section":"ATTROPTIONALDATA","key":"joint_actual_position"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "getOptionalInfoConfig", "value": 1}

Modify the Configuration of optionalInfoConfig

Send message:

{"cmdName":"setOptionalInfoConfig","section":"PORTCONFIG","key":"port10000_delay_ms", "value": "200"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "setOptionalInfoConfig"}

Send message:

{"cmdName":"setOptionalInfoConfig","section":"ATTROPTIONALDATA","key":"joint_actual_position", "value": 0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "setOptionalInfoConfig"}

Available Interfaces

The use of each commands is introduced in the following sections divided by different functions. The meaning of returned fields are explained under each command.

Basic Robots Operations

Power On

Send message:

{"cmdName":"power_on"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "power_on"}

Power Off

Send message:

{"cmdName":"power_off"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "power_off"}

Enable the Robot

Send message:

{"cmdName":"enable_robot"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "enable_robot"}

Disable the Robot

Send message:

{"cmdName":"disable_robot"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "disable_robot"}

Shut Down the Control Cabinet

Send message:

{"cmdName":"shutdown"}

Receive message:

null

After sending the command, the controller terminates the process, and the TCP server closes, so no message is returned.

Get Robot State

Send message:

{"cmdName":"get_robot_state"}

Receive message:

{"enable": true, "power": 1, "errorMsg": "", "errcode": 0, "cmdName": "get_robot_state", "errorCode": "0", "msg": ""}

Note:

  • enable:Whether the robot is enabled. True means enabled. False means not enabled.
  • power:Whether the robot is powered on. 1 means powered on. 0 means not powered on.
  • errorCode: The corresponding error code.
  • errcode: The error code returned by the controller.
  • errorMsg:The corresponding error message.
  • msg: The error message returned by the controller.

Get the Controller's Version

Send message:

{"cmdName":"get_version"}

Receive message:

{"errorMsg": "", "cmdName": "get_version", "errorCode": "0", "robot_name": "JKROBOT", "version": "1.7.1_40_rc_X64", "robot_id": "Zu20200100"}

Note:

  • robot_name:Robot name
  • version:Robot controller version
  • robot_id:Robot ID

Get the Robot's Mounting Angle

Send message:

{"cmdName":"get_installation_angle"}

Receive message:

{"installation_angle": [[x, y, z, w], [rx, ry , rz]], "errorCode": "0", "cmdName": "get_installation_angle", "errorMsg": ""}

Note:

  • x, y, z, w Mounting angle quaternion representation.
  • rx, ry, rz Mounting angle euler angle representation.

Set the Robot's Mounting Angle

Send message:

{"cmdName":"set_installation_angle","angleX":angleX,"angleZ": angleZ}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_installation_angle"}

Note:

  • angleX:Robot rotation angle in the X direction, range: [0, 180] degrees.
  • angleZ:Robot rotation angle in the Z direction, range: [0, 360) degrees.

Robot Motions

JOG

The Jog command includes single-axis motion in joint space and single-axis motion in Cartesian space.

  • jog_mode Mode of motions, including:

    • Jog_stop (stop jogging): 0
    • Continue (continuous moving): 1
    • Increment (incremental moving): 2
    • ABS (absolute moving): 3
  • coord_map Selection of coordinate system, including:

    • Move in the world coordinate system: 0
    • Move in the joint space: 1
    • Move in the tool coordinate system: 2
  • jnum The joint number in joint space. 0 means joint 1.

  • jnum x, y, z, rx, ry, and rz, corresponding to numbers 0 to 5 in Cartesian space.

  • jogvel Velocity

  • poscmd The stepping value. For single-joint motion, the unit is degrees (deg), and for single-axis motion in space, the unit is millimeters (mm).

When jog_mode is 0, only the jog_mode, coord_map, and jnum parameters are effective.

Send message:

{"cmdName":"jog","jog_mode":0, "coord_map":1, "jnum":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "jog"}

Note:

  • The sent command represents stopping the robot's joint 2 jog motion in joint space.

When jog_mode is 1, only the jog_mode, coord_map, jnum, and jogvel parameters are effective.

Send message:

{"cmdName":"jog","jog_mode":1, "coord_map":1, "jnum":1, "jogvel":30}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "jog"}

Note:

  • The sent command represents the robot performing jog motion in joint space, with joint 2 moving at 30 deg/s.
  • It is important to note that the direction of motion (positive or negative) is determined by the sign of jogvel.
  • The current axis motion must be stopped before issuing another motion command for the same axis.

When jog_mode is 2, the parameters jog_mode, coord_map, jnum, jogvel, and poscmd are all effective.

Send message:

{"cmdName":"jog","jog_mode":2, "coord_map":1, "jnum":1, "jogvel":30, "poscmd":20}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "jog"}

Note:

  • The sent command controls the robot's joint 2 to move in the positive direction at 30 deg/s for 20 degrees.
  • The direction of motion (positive or negative) can be determined by the sign of poscmd.

When jog_mode is 3, the parameters jog_mode, coord_map, jnum, jogvel, and poscmd are all effective.

Send message:

{"cmdName":"jog","jog_mode":3, "coord_map":1, "jnum":1, "jogvel":30, "poscmd":20}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "jog"}

Note:

  • The sent command controls the robot's joint 2 to move at 30 deg/s speed to the target position of 20 degrees.

MoveJ

Send message:

{"cmdName":"joint_move","relFlag":0,"jointPosition":[0,90.5,90.5,0,90.5,0],"speed":20.5,"accel":20.5}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "joint_move"}

Note:

  • relFlag: The optional values are 0 or 1. 0 represents absolute motion, and 1 represents relative motion.
  • jointPosition:[j1,j2,j3,j4,j5,j6] The value entered represents the angle for each joint. The unit is degrees. The direction of motion (positive or negative) is determined by the sign of the jointPosition value.
  • speed: speed_val Represents the joint velocity, with the unit in (°/s). Users can enter a suitable parameter based on their needs.
  • accel:accel_val Represents the joint acceleration, with the unit in (°/s²). Users can enter a suitable parameter. It is recommended that the acceleration value should not exceed 720.
  • joint_move It is a blocking motion command (internal to the controller, without affecting the immediate return of the instruction). The next motion command will only be executed after the current one is completed. If immediate execution of the next instruction is required, it is recommended to first use the stop_program command to stop the current motion before sending the next motion command.

The TCP End Moves to the Specified Position

Send message:

{"cmdName":"end_move","endPosition":[100,200.1,200.5,0,0,0], "speed":21.5, "accel":31.5}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "end_move"}

Note:

  • endPosition: [x,y,z,a,b,c] specifies the value of xyzabc of the TCP end.
  • speed: speed_val represents the speed of the joint in degrees/S, and the user can fill in the appropriate parameters. If speed_val is set to 20, it means the joint speed is 20°/S.
  • accel:accel_val represents the acceleration of the joint in (°/S²).The user can enter appropriate parameters, and the acceleration is recommended to be less than 720.
  • end_move is a block move command that one move command will only be executed after the proceeding move command is executed. If the next command needs to be executed immediately, it is recommended to use stop_program to stop the current movement first, and then send the next move command.
  • end_move command does not move from the current position to the target position point in a straight line. This command first performs the inverse solution to the target point of cartesian space input by the user, and then uses the joint_move command to make the robot joint move to the specified position.
  • If you want to move from the current position to the target position point in a straight line, use the moveL command.

MoveL

Send message:

{"cmdName":"moveL","relFlag":1,"cartPosition":[0,0,50,0,0,0],"speed":20,"accel":50,"tol":0.5}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "moveL"}

Note:

  • cartPosition:[x,y,z,rx,ry,rz] specify the values for Cartesian space.
  • speed:speed_val The linear speed in mm/s, and the user can input appropriate parameters. If speed_val is set to 20, it means the linear speed is 20 mm/s.
  • accel:accel_val The acceleration of linear move(mm/S²). The user can enter appropriate parameters and the value of Accel is recommended not to exceed 8000.
  • relFlag:flag_val Can set 0 or 1. 0 stands for absolute movement, 1 stands for relative movement.
  • moveL is a block move command that one move command will only be executed after the proceeding move command is executed. If the next command needs to be executed immediately, it is recommended to use stop_program to stop the current movement first, and then send the next move command.

MoveC

Send message:

{"cmdName":"movc","relFlag":move_mode,"pos_mid":[x,y,z,rx,ry,rz],"pos_end":[x,y,z,rx,ry,rz],"speed":vel,"accel":acc,"tol":tol}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "movc"}

Note:

  • pos_mid:[x,y,z,rx,ry,rz] specifies the value of x,y,z,rx,ry,rz in Cartesian space.
  • pos_end:[x,y,z,rx,ry,rz] specifies the value of x,y,z,rx,ry,rz in Cartesian space.
  • speed:speed_val represents the speed of the joint in degrees/S, and the user can fill in the appropriate parameters. If speed_val is set to 20, it means the joint speed is 20°/S.
  • accel:accel_val represents the acceleration of the joint in (°/S²). The user can enter appropriate parameters, and the acceleration is recommended to be less than 720.
  • tol:Maximum tolerance of error, or 0 if not required.

Get the Motion State

Send message:

{"cmdName":"get_motion_state"}

Receive message:

{"queue": 0, "errorMsg": "", "cmdName": "get_motion_state", "queue_full": false, "active_queue": 0, "inpos": true, "paused": false, "err_add_line": 0, "errorCode": "0", "motion_line": 0}

Note:

  • queue_full: Check whether the queue is in a full state. 0 means not full; 1 means full.
  • queue: The number of motion commands in the queue.
  • inpos: The position status flag. 0 means not at the position (i.e., in motion), and 1 means at the position (typically in a stopped state).
  • paused: Motion pause status flag. 0 means not paused, and 1 means in a paused state.
  • err_add_line: If it is a repeated command that the controller does not execute, the line number of the motion command.
  • motion_line: The ID of motion commands.

Get the DH Parameters of the Robot

Send message:

{"cmdName":"get_dh_param"}

Receive message:

{"errorCode": "0", "errorMsg": "", "dh_param": [[0.0, 90.0, 0.0, 0.0, 90.0, -90.0], [0.0, 0.0, 897.0, 744.5, 0.0, 0.0], [196.5, 0.0, 0.0, -188.35000610351562, 138.5, 120.5], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]], "cmdName": "get_dh_param"}

Note:

  • dh_param: In the returned list, each element represents the following in order by index: alpha, a, d, joint_homeoff.
    • alpha: link twist angle
    • a: link length
    • d: link offset
    • joint_homeoff: joint zero offset

Get User Coordinate System

Send message:

{"cmdName":"get_user_offsets"}

Receive message:

{"user_offsets": [[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]], "errorCode": "0", "cmdName": "get_user_offsets", "errorMsg": ""}

Note:

  • tool_offset:There are 16 sets of data (0 to 15), corresponding to the offset of the tool coordinate system relative to the ID, where 0 represents the default world coordinate system.

Get the Current User Coordinate System

Send message:

{"cmdName":"get_curr_user_offset"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_curr_user_offset", "user_offset": [-590.0, 380.0, -1230.0, 0.0, 0.0, 0.0]}

Set User Coordinate System

Send message:

{"cmdName":"set_user_id","user_frame_id":2}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_user_id"}

Note:

  • set_user_id: User coordinate system ID. It is used to select the coordinate system in which to move. For example, setting the ID to 2 means moving in the second user coordinate system.
  • It is important to note that when set_user_id is set to 0, it means the robot moves in the base coordinate system (world coordinate system).

Get the Current User Coordinate System

Send message:

{"cmdName":"get_curr_user_id"}

Receive message:

{"errorCode": "0", "errorMsg": "", "id": 10, "cmdName": "get_curr_user_id"}

Set the User Coordinate System

Send message:

{"cmdName":"set_user_offsets","userffset":[10,10,10,10,10,10],"id":2,"name":"user_new"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_user_offsets"}

Note:

  • userffset: Input the x, y, z, rx, ry, rz of the User coordinate system, as shown in the example:[10,10,10,10,10,10]。
  • id: The ID number of the user coordinate system to be set. The available IDs range from 1 to 15. For example, setting the user coordinate system to 2.
  • name: The name of the user coordinate system to be set. For example, setting the name to "user_new."
  • This command only sets the coordinate system value, but the coordinate system has not actually been selected

Set Tool Coordinate System

Send message:

{"cmdName":"set_tool_id","tool_id":2}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tool_id"}

Note:

  • tool_id: Tool coordinate system ID. It is used to select the coordinate system in which to move. For example, setting the ID to 2 means moving in the second tool coordinate system.
  • It is important to note that when tool_id is set to 0, the robot's tool is defaulted to the center of the end flange.

Get the Current Tool Coordinate System

{"cmdName":"get_curr_tool_id"}

Receive message:

{"errorCode": "0", "errorMsg": "", "id": 2, "cmdName": "get_curr_tool_id"}

Set Tool Coordinate System

Send message:

{"cmdName":"set_tool_offsets","tooloffset":[10,10,10,10,10,10],"id":2,"name":"tcp_new"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tool_offsets"}

Note:

  • tooloffset:Enter the x, y, z, rx, ry, and rz values of the tool coordinate system. For example [10, 10, 10, 10, 10, 10].
  • id:The ID number of the tool coordinate system to be set. The available IDs range from 1 to 15. For example, setting the tool coordinate system to 2.
  • name:The name of the tool coordinate system to be set. For example, setting the name to "tcp_new".

Get Tool Coordinate System

Send message:

{"cmdName":"get_tool_offsets"}

Receive message:

{"errorCode": "0", "errorMsg": "", "tool_offsets": [[0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]], "cmdName": "get_tool_offsets"}

Note:

  • tool_offset: There are 16 sets of data (0 to 15), corresponding to the offset of the tool coordinate system relative to the ID. 0 represents the default end flange center coordinate system.

Get the Current Tool Coordinate System

Send message:

{"cmdName":"get_curr_tool_offset"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_curr_tool_offset", "tool_offset": [0.0, 0.0, 130.0, 0.0, 0.0, -90.0]}

Set Payload

Send message:

{"cmdName":"set_payload","mass":m,"centroid":[x,y,z]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_payload"}

Note:

  • mass is the mass of the payload, in kilograms (KG). centroid is the center of mass of the payload, in millimeters (mm). For example, if the payload mass is set to 1 KG and the center of mass is [10, 10, 10], the command to send would be:
{"cmdName":"set_payload","mass":1,"centroid":[10,10,10]}

Get Payload

Send message:

{"cmdName":"get_payload"}

Receive message:

{"errorCode": "0", "centroid": [0.0, 0.0, 1.0], "mass": 1.0, "cmdName": "get_payload", "errorMsg": ""}

Note:

  • mass:It is the mass of the payload, with the unit in kilograms (KG).
  • centroid:It is the center of mass of the payload, with the unit in millimeters (mm).

Get Joint Position

Send message:

{"cmdName":"get_joint_pos"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_joint_pos", "joint_pos": [j1,j2,j3,j4,j5,j6]}

Note:

  • j1,j2,j3,j4,j5,j6 The six returned joint positions, unit is degree.

Get the End Tool Pose of the Current Coordinate System

Send message:

{"cmdName":"get_tcp_pos"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": " get_tcp_pos", "tcp_pos": [x,y,z,a,b,c]}

Note:

  • [x,y,z,a,b,c] It is the end-effector pose in the currently set tool coordinate system. By default, the tool coordinate system is the center of the flange.

Set the Robot Speed Rate

{"cmdName":"rapid_rate","rate_value":0.2}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "rapid_rate"}

Note:

  • rate_value:By default, the robot's program execution speed is 1. This command allows you to modify it, with the range being from 0 to 1.

Whether in Soft Limit

Send message:

{"cmdName":"is_on_limit"}

Receive message:

{"errorCode": "0", "errorMsg": "", "on_limit": 0, "cmdName": "is_on_limit"}

Note:

  • on_limit: True means in soft limit. False means not.

Whether in Emergency Stop Status

Send message:

{"cmdName":"emergency_stop_status"}

Receive message:

{"errorCode": "0", "errorMsg": "", "emergency_stop": 0, "cmdName": "emergency_stop_status"}

Note:

  • emergency_stop:It indicates whether the robot is in an emergency stop state. 0 means not in an emergency stop state; 1 means in an emergency stop state.

Set Motion Planner

Send message:

{"cmdName":"set_motion_planner","type":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_motion_planner"}

Note:

  • type:Motion planner type. The available values are -1, 0, and 1. -1 means the planner is disabled, 0 means using T-planning, and 1 means using S-planning.

Get the Actual Joint Position

Send message:

{"cmdName":"get_actual_joint_pos"}

Receive message:

{"errorCode": "0", "position": [285.8061097309843, 80.09823788479945, 60.72657603991451, 124.99045041547085, -85.27718451168131, 316.9348226974971], "cmdName": "get_actual_joint_pos", "errorMsg": ""}

Note:

  • position:Returns a six-dimensional list representing the joint angles of each joint.

Get the Current Actual Cartesian Pose

Send message:

{"cmdName":"get_actual_tcp_pos"}

Receive message:

{"errorCode": "0", "position": [604.2014815031182, -71.01229318144345, 1669.033510162098, -179.4141090762053, -6.279762125819193, 149.01179247501761], "cmdName": "get_actual_tcp_pos", "errorMsg": ""}

Note:

  • Returns a six-dimensional list representing the Cartesian pose in each dimension.

Get the Current Speed Rate

Send message:

{"cmdName":"get_rapid_rate"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_rapid_rate", "value": 1.0}

Note:

  • value:Current Speed Rate, range is [0,1]

Servo

Whether in Servo Mode

Send message:

{"cmdName":"is_in_servomove"}

Receive message:

{"errorCode": "0", "errorMsg": "", "in_servomove": true, "cmdName": "is_in_servomove"}

Note:

  • in_servomove:true, in servo mode. false, not.

Whether in Servo Move Mode

Send message:

{"cmdName":"servo_move","relFlag":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "servo_move"}

Note:

  • relFlag: 1 means yes, 0 means no.

ServoJ

Send message:

{"cmdName":"servo_j","relFlag":1,"jointPosition":[0.1,0,0,0,0,0],"stepNum":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "servo_j"}

Note:

  • Users can generate the six joint angles themselves and send them to the robot, which will control the robot to reach the corresponding target position.
  • Before using the servo_j command, users need to first use the servo_move command to enter the servo position control mode.
  • jointPosition: [joint1, joint2, joint3, joint4, joint5, joint6] – These are the angles of each joint, with the unit in degrees.
  • relFlag: The relFlag optional parameter can be 0 or 1. 0 represents absolute motion, and 1 represents relative motion.
  • stepnum: This is the cycle division factor. The robot will execute the received servo motion command at a cycle of num * 8ms.
  • It is important to note that because the controller’s control cycle is 8ms, this command needs to be sent every 8ms to be effective. It must be sent continuously for it to work; sending it once will have no effect. Additionally, the maximum joint speed is 180 degrees/second. For example, [1.5, 0.5, 0.5, 0.5, 0.5, 0.5], where 1.5/0.008 = 187.5, exceeds the joint speed limit, and the servo_j command will not take effect.

Please note:

This command differs significantly from joint_move. It is primarily used in research for trajectory planning. When this command is sent to the robot, it bypasses the controller's planner and is directly sent to the servo. Users need to pre-plan the trajectory when using this command; otherwise, the result will be poor and fail to meet expectations. Under normal circumstances, it is recommended to use the joint_move command.

Cartesian Space Position Control Mode

Send message:

{"cmdName":"servo_p","catPosition":[x,y,z,a,b,c],"relFlag":0,"stepNum":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "servo_p"}

Note:

  • Users can use their own trajectory planning algorithms to generate the joint coordinates and then send them to the robot’s six joints, enabling the robot to execute these commands.
  • Before using the servo_p command, users need to first use the servo_move command to enter the servo position control mode.
  • catPosition: [x, y, z, a, b, c] – Represents the robot's coordinates in Cartesian space, where x, y, z are in mm, and a, b, c are in degrees.
  • a, b, and c represent the robot's pose in Euler angle order XYZ.
  • relFlag: The relFlag optional parameter can be 0 or 1. 0 represents absolute motion, and 1 represents relative motion.
  • stepnum: This is the cycle division factor. The robot will execute the received servo motion command at a cycle of num * 8ms.
  • It is important to note that this command needs to be sent every 8ms to be effective because the controller interpolates a position point every 8ms. Also, the values for x, y, z, a, b, and c should not be too large to avoid exceeding the controller's safe speed limit.

Please note:

This command is mainly used in research for trajectory planning. When using this command, the controller's planner does not perform interpolation. Users need to pre-plan the trajectory when using this command; otherwise, the result will be poor and fail to meet expectations. Under normal circumstances, it is recommended to use moveL.

Servo Mode Filter

  • set_servo_move_filter sets the servo mode filter to assist in trajectory planning.
  • filter_type means there are 6 modes:
    • no filter:0
    • first-order low-pass filter in joint space:1
    • nonlinear filter in joint space:2
    • multi-order moving average filter in joint space:3
    • nonlinear filter in Cartesian space:4
    • velocity feedforward:5

When filter_type is 0, there is only 1 parameter.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • Disable the filter and do not use the filter for assistive planning. This needs to be set after exiting servo mode.

When filter_type is 1, there are only 2 parameters.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":1",lpf_cf":0.5}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • To set the first-order low-pass filter in joint space, it needs to be configured after exiting servo mode.
  • lpf_cf represents the cutoff frequency, in Hz.

When filter_type is 2, there are only 4 parameters.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":2,"nlf_max_vr":2,"nlf_max_ar":2,"nlf_max_jr":4}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • To set the joint space nonlinear filter, it needs to be configured after exiting servo mode.
  • max_vr represents the maximum rate of change in attitude speed (absolute value), in °/s.
  • max_ar represents the maximum acceleration of attitude change speed (absolute value), in °/s².
  • max_jr represents the maximum jerk (rate of change of acceleration) of attitude change speed (absolute value), in °/s³.

When filter_type is 3, there are only 5 parameters.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":3,"mmf_max_buf":20,"mmf_kp":0.1,"mmf_kv":0.2,"mmf_ka":0.6}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • Setting joint space multi-order moving average filter requires exiting the servo mode before configuring.
  • mmf_max_buf: The filter window width. The larger the value, the smoother the filtered trajectory, but it may reduce accuracy.
  • mmf_kp: Position tracking coefficient. The smaller the value, the smoother the filtered trajectory. The larger the value, the higher the accuracy, but there may be oscillation.
  • mmf_kv: Velocity tracking coefficient. The smaller the value, the smoother the filtered trajectory. The larger the value, the higher the accuracy, but there may be oscillation.
  • mmf_ka: Acceleration position tracking coefficient. The smaller the value, the smoother the filtered trajectory. The larger the value, the higher the accuracy, but there may be oscillation.

When filter_type is 4, there are only 7 parameters.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":4,"nlf_max_vr":2,"nlf_max_ar":2,"nlf_max_jr":4,"nlf_max_vp":10,"nlf_max_ap":100,"nlf_max_jp":200}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • The Cartesian space nonlinear filter must be set after exiting servo mode.*
  • max_vr is the maximum allowable angular velocity (in absolute value) for changes in posture in Cartesian space, measured in °/s.
  • max_ar is the maximum allowable angular acceleration (in absolute value) for changes in posture in Cartesian space, measured in °/s².
  • max_jr is the maximum allowable angular jerk (in absolute value) for changes in posture in Cartesian space, measured in °/s³.
  • max_vp is the maximum allowable velocity (in absolute value) for movement commands in Cartesian space, measured in mm/s.
  • max_ap is the maximum allowable acceleration (in absolute value) for movement commands in Cartesian space, measured in mm/s².
  • max_jp is the maximum allowable jerk (in absolute value) for movement commands in Cartesian space, measured in mm/s³.

When filter_type is 5, there are only 3 parameters.

Send message:

{"cmdName":"set_servo_move_filter","filter_type":5,"mmf_max_buf":max_buf,"mmf_kp":kp}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_servo_move_filter"}

Note:

  • The multi-order moving average filter in joint space must be set after exiting servo mode.
  • max_buf is the size of the moving average filter buffer.
  • mmf_kp is the acceleration filtering coefficient.

Enable the Drag Mode

Send message:

{"cmdName":"torque_control_enable","enable_flag":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "torque_control_enable"}

Note:

  • enable_flag,0 means disabled, 1 means enabled.

Get Drag Status

Send message:

{"cmdName":"get_drag_status"}

Receive message:

{"status": false, "errorCode": "0", "cmdName": "get_drag_status", "errorMsg": ""}

Note:

  • drag_status: True indicates that the robot is in drag mode, and the user can perform drag programming on the robot; False indicates the opposite.

IO

Set DO Value

Send message:

{"cmdName":"set_digital_output","type":0,"index":1,"value":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_digital_output"}

Note:

  • type is the type of the Digital Output (DO):
    • 0 – Controller AO;
    • 1 – Tool IO;
    • 2 – Expansion AO;
    • 3 – Reserved;
    • 4 – Modbus IO;
    • 5 – Profinet IO;
    • 6 – Ethernet/IP IO.
  • index is the identifier of the DO. To control the 1st DO, set the value of index to 1. Note that indexing starts from 1.
  • value is the value of the DO, with possible values of 0 or 1.

Get DO Value

Send message:

{"cmdName":"get_digital_output","type":0,"index":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_digital_output", "value": 0}

Note:

  • type is the type of the Digital Output (DO):
    • 0 – Controller AO;
    • 1 – Tool IO;
    • 2 – Expansion AO;
    • 3 – Reserved;
    • 4 – Modbus IO;
    • 5 – Profinet IO;
    • 6 – Ethernet/IP IO.
  • index is the identifier of the DO. For example, the DO numbers for control range from 1 to 31. To control the 31st DO, set the value of index to 31. Note that indexing starts from 1.
  • value is the value of the DO, with possible values of 0 or 1.

Get DI

Send message:

{"cmdName":"get_digital_input","type":0,"index":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_digital_input", "value": 0}

Note:

  • type is the type of the Digital Input (DI):
    • 0 – Controller AO;
    • 1 – Tool IO;
    • 2 – Expansion AO;
    • 3 – Reserved;
    • 4 – Modbus IO;
    • 5 – Profinet IO;
    • 6 – Ethernet/IP IO.
  • index is the identifier of the DO. For example, the DO numbers for control range from 1 to 31. To control the 31st DO, set the value of index to 31. Note that indexing starts from 1.
  • value is the value of the DO, with possible values of 0 or 1.

Get DI Status

Send message:

{"cmdName":"get_digital_input_status"}

Receive message:

{"din_status": [1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], "errorCode": "0", "cmdName": "get_digital_input_status", "errorMsg": ""}

Note:

  • din_status: There are a total of 136 pins. The first 8 pins are used for the control cabinet hardware IO. The remaining pins are for Modbus.

Set AO Value

Send message:

{"cmdName":"set_analog_output","type":type,"index":index,"value":value}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_analog_output"}

Note:

  • type is the type of the Analog Output (AO):

    • 0 – Controller AO;
    • 1 – Tool IO;
    • 2 – Expansion AO;
    • 3 – Reserved;
    • 4 – Modbus IO;
    • 5 – Profinet IO;
    • 6 – Ethernet/IP IO.
  • index is the identifier of the AO. For example, the AO numbers for control range from 0 to 7. To control the 7th AO, set the value of index to 7.

  • value is the value of the AO, where a floating-point number can be input to meet programming requirements.

Get AO Value

Send message:

{"cmdName":"get_analog_output","type":0,"index":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_analog_output", "value": 0.0}

Note:

  • type is the type of the Analog Output (AO):

    • 0 – Controller AO;
    • 1 – Tool IO;
    • 2 – Expansion AO;
    • 3 – Reserved;
    • 4 – Modbus IO;
    • 5 – Profinet IO;
    • 6 – Ethernet/IP IO.
  • index is the identifier of the AO. For example, the AO numbers for control range from 0 to 7. To control the 7th AO, set the value of index to 7.

  • value is the value of the AO, where a floating-point number can be input to meet programming requirements.

Get Extension IO Status

Send message:

{"cmdName":"get_extio_status"}

Receive message:

  • When there is no extension module:
(0, [], {'state': 0})
  • When there is extension module:
{
    "errorCode": "0",
    "errorMsg": "",
    "cmdName": "get_extio_status",
    "extio_status": {"status": "[[0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], [0, 0, 0, 0, 0, 0, 0, 0], [], []]", "setup": "[[0, \"11\", [9600, 8, 1, 78, 1], [[1, 8], [17, 8], [0, 0], [0, 0]], \"ext_0kakhfa54n84kl8k\"], [1, \"22\", [\"192.168.1.200\", 1111, 2], [[1, 8], [0, 0], [0, 0], [0, 0]], \"ext_9ckraca694bm6gm9\"]]", "num": 2, "pinmap": "[[0, 0, 0, 0], [8, 8, 0, 0]]", "mode": 0}}
    }

Note:

  • num: Represents the number of external expansion IO modules.
  • mode: Indicates whether the expansion IO is running.
  • setup: (1, 'mobusIoName', ('192.168.2.47', 8888)) 1 stands for TCP and 0 stands for RTU. modbusIoName stands for the name of the external extension module, and ('192.168.2.47', 8888) stands for the IP and port.
  • {'ai': (0, 0), 'do': (0, 0), 'ao': (0, 0), 'di': (0, 8)} : The 1st digit in the brackets stands for the initial assigned address of the external extension module register. The 2nd digit stands for the number of IO.
  • pinmap: The starting address of the external module's pin index, which needs to be considered when there are multiple external modules.
  • {'state': 0, 'di': (0, 0, 0, 0, 0, 0, 0, 0)})"}: state 0 means the extension module is not running, and 1 means the extension module is running.

Get the Status of the Function Input Pin

Send message:

{"cmdName":"get_funcdi_status"}

Receive message:

{"errorCode": "0", "errorMsg": "", "funcdi_status": [[-1, -1], [-1, -1], [-1, -1], [-1, -1], [-1, -1], [-1, -1], [-1, -1], [-1, -1], [0,2], [-1,- 1], [-1, -1], [-1, -1]], "cmdName": "get_funcdi_status"}

Note:

  • funci_status:A total of 12 function input pins are returned, which are:

    • start program
    • pause program
    • resume program
    • stop program
    • power on
    • power off
    • enable robot
    • disable robot
    • level 1 reduced mode
    • protective stop
    • back to original position
    • level 2 reduced mode
  • [type,index]:[-1,-1] is the default value, indicating that no input pin is set as the function pin.

    • Type means:

      • 0 the input pin of cabinet.
      • 1 the input pin of robot end tool.
      • 2 the input pin of modbus.
    • Index the index number of the input pin, indicating which pin is set as the function pin. The above [0,2] indicates the third pin of the cabinet (the index starts at 0) is set as the level 1 reduced mode function pin.

TIO

Set TIO V3 Tool Voltage

Send message:

{"cmdName":"set_tio_vout_param","tio_vout_ena":0,"tio_vout_vol":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tio_vout_param"}

Note:

  • tio_vout_ena 0 or 1; 0 means enabled, 1 means unenabled.

  • tio_vout_vol 0 or 1; 0 is 24V, 1 is 12V.

Get TIO V3 Tool Voltage

Send message:

{"cmdName":"get_tio_vout_param"}

Receive message:

{"errorCode": "0", "errorMsg": "", "tio_vout_ena": 0, "tio_vout_vol": 0, "cmdName": "get_tio_vout_param"}

Note:

  • tio_vout_ena 0 or 1; 0 means enabled, 1 means unenabled.

  • tio_vout_vol 0 is 12V, 1 is 24V.

Add or Modify Signals

Send message:

{"cmdName":"add_tio_rs_signal","tio_signal_name":<>,"tio_signal_chnId":<>,"tio_signal_sigType":<>,"tio_signal_sigAddr":<>,"frequency":<>}

Receive message: {"errorCode": "0", "errorMsg": "", "cmdName": "add_tio_rs_signal"} Note:

  • tio_signal_name: Identifier name (limited to 20 characters).
  • tio_signal_chnId: RS485 channel ID
  • tio_signal_sigType: Signal type
  • tio_signal_sigAddr: Register address
  • frequency: The signal refresh rate within the controller should not exceed 10.

Get RS485 Signal List

Send message:

{"cmdName":"get_rs485_signal_list"}

Receive measage:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_rs485_signal_list", "num":<>, </signalName>:<> }

Note:

  • num The number of signals
  • signalName: signalName: { “chnId”:<>, “sigType”:<:>, “sigAddr”:<>, “value”:<>, “frequency”:<> }

Delete RS485 Signal

Send message:

{"cmdName":"del_tio_rs_signal","tio_signal_name":"test"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "del_tio_rs_signal"}

Note:

  • tio_signal_name:signal name

Set TIO Mode

Send message:

{"cmdName":"set_tio_pin_mode","pinType":<>,"pinMode":<>}

Receive message

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tio_pin_mode"}

Note:

  • pinType:tio type 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
  • pinMode:tio mode.
    • DI Pins:
      • 0:0x00 DI2 is NPN, DI1 is NPN
      • 1:0x01 DI2 is NPN, DI1 is PNP
      • 2:0x10 DI2 is PNP, DI1 is NPN
      • 3:0x11 DI2 is PNP, DI1 is PNP
    • DO Pins: The lower 8 bits of data: the high 4 bits represent the DO2 configuration, and the lower 4 bits represent the DO1 configuration. 0x0 DO indicates NPN output.
      • 0x1 DO is PNP output, 0x2 DO is push-pull output, and 0xF is the RS485H interface.
    • AI Pins:
      • 0:Analog input function enabled, RS485L disabled.
      • 1:RS485L interface enabled, analog input function disabled.

Get TIO Mode

Send message:

{"cmdName":"get_tio_pin_mode","pinType":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_tio_pin_mode", "pinMode": <>}

Note:

  • pinType:tio type. 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
  • pinMode:tio mode.
    • DI Pins:
      • 0:0x00 DI2 is NPN,DI1 is NPN
      • 1:0x01 DI2 is NPN,DI1 is PNP
      • 2:0x10 DI2 is PNP,DI1 is NPN
      • 3:0x11 DI2 is PNP,DI1 is PNP
    • DO Pins: The lower 8 bits of data: the high 4 bits represent the DO2 configuration, and the lower 4 bits represent the DO1 configuration. 0x0 DO indicates NPN output.
      • 0x1 DO is PNP output, 0x2 DO is push-pull output, and 0xF is the RS485H interface.
    • AI Pins:
      • 0:Analog input function enabled, RS485L disabled.
      • 1:RS485L interface enabled, analog input function disabled.

Set RS485 Communication Parameters

Send message:

{"cmdName":"set_rs485_chn_comm","chn_id":<>,"slaveId":<>,"baudrate":<>,"databit":<>,"stopbit":<>,"parity":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_rs485_chn_comm"}

Note:

  • chn_id:When querying the RS485 channel ID, chn_id is used as the input parameter.
  • slaveId: When the channel mode is set to Modbus RTU, the Modbus slave node ID must be specified. For other modes, this can be ignored.
  • baudrate:baudrate 4800,9600,14400,19200,38400,57600,115200,230400
  • databit: databit 7,8
  • stopbit: stopbit 1,2
  • parity: parity bit: 78 → No parity, 79 → Odd parity, 69 → Even parity.

Get RS485 Communication Parameters

Send message:

{"cmdName":"get_rs485_chn_comm","chn_id":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": 34,"get_rs485_chn_comm","slaveId":<>,"baudrate":<>,"databit":<>,"stopbit":<>,"parity":<>}

Note:

  • chn_id:When querying the RS485 channel ID, chn_id is used as the input parameter.
  • slaveId:When the channel mode is set to Modbus RTU, the Modbus slave node ID must be specified. For other modes, this can be ignored.
  • baudrate:baudrate 4800,9600,14400,19200,38400,57600,115200,230400
  • databit:databit 7,8
  • stopbit:stopbit 1,2
  • parity:parity bit: 78 → No parity, 79 → Odd parity, 69 → Even parity.

Set RS485 Communication Mode

Send message:

{"cmdName":"set_rs485_chn_mode","chnId":<>,"chnMode":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_rs485_chn_mode"}

Note:

  • chnId: 0: RS485H, channel 1; 1: RS485L, channel 2
  • chnMode: 0: Modbus RTU, 1: Raw RS485, 2, torque sensor

Get RS485 Communication Mode

Send message:

{"cmdName":"get_rs485_chn_mode","chnId":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_rs485_chn_mode", "chnMode": <>}

Note:

  • chnId: 0: RS485H,channel 1; 1: RS485L,channel 2
  • chnMode: 0: Modbus RTU。1: Raw RS485。2:torque sensor

Send Command via RS485

Send message:

{"cmdName":"send_tio_rs_command","chn_id":<>,"cmbBuf":<>}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "send_tio_rs_command"}

Note:

  • chn_id:channel ID
  • cmdBuf:data field

Get TIO Signals

Send message:

{"cmdName":"get_tio_signals"}

Receive message:

{"signals": [["ttt", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0], ["", 0, 0, 0, 0, 0.0]], "errorCode": "0", "cmdName": "get_tio_signals", "errorMsg": ""}

Note:

  • signals: Returns a list of signal quantities, an 8-element list.
  • The first element is the signal name.
  • The subsequent elements in the list are:
    • chn_id: Channel ID.
    • signal_type: Type of the signal.
    • signal_addr: Signal address.
    • value: The value of the signal.
    • frequency: Signal refresh frequency.

Program

Load Program

Send message:

{"cmdName":"load_program","programName":"track/test.jks"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "load_program"}

Note:

  • programName does not support Chinese characters.
  • If the controller is version 1.5 or earlier, the file should have a .ngc extension; for versions 1.5 and later, the file should have a .jks extension.
  • When loading a trajectory file, prefix the file name with track/.

Get Loaded Program Name

Send message:

{"cmdName":"get_loaded_program"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_loaded_program", "programName": "test.jks"}

Run Program

Send message:

{"cmdName":"play_program"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "play_program"}

Pause Program

Send message:

{"cmdName":"pause_program"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "pause_program"}

Resume Program

Send message:

{"cmdName":"resume_program"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "resume_program"}

Stop Program

Send message:

{"cmdName":"stop_program"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "stop_program"}

Note:

  • Stopping the program essentially stops the robot’s movement.
  • stop_program can also be used to stop other movement commands of the robot, such as joint_move or moveL. It is recommended to use stop_program when you want to control the robot to stop its motion.

Get Program Status

Program status:running/pause/idle

Send message:

{"cmdName":"get_program_state"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_program_state", "programState": "idle"}

Query User-defined Variable

Send message:

{"cmdName":"query_user_defined_variable"}

Receive message:

{"errorCode": "0", "errorMsg": "", "var_list": [{"alias": "test", "id": 5500, "value": 1.0}], "cmdName": "query_user_defined_variable"}

Note:

  • var_list: Returns a list of all user-defined system variables.
  • alias: The name of the system variable.
  • id:The ID number of the system variable. To modify a system variable, the user needs to know its ID number.
  • value:The value of the system variable. For example, in the returned message, the system variable name is system_var1, the ID is 5500, and the value is 1.0.

Modify User-defined Variable

Send message:

{"cmdName":"modify_user_defined_variable","id_new":5500,"alias_new":"s_new","value_new":14}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName":"modify_user_defined_variable"}

Note:

  • id_new:The ID number of the system variable to be modified. The ID can be obtained using the query_user_defined_variable command.
  • alias_new:The new name to set for the system variable.
  • value_new:The new value to set for the system variable.

Get Current Line

Send message:

{"cmdName":"get_current_line"}

Receive message:

{"current_line": 0, "errorCode": "0", "cmdName": "get_current_line", "errorMsg": ""}

Note:

  • current_line:current line.

Get Program Information

Send message:

{"cmdName":"get_program_info"}

Receive message:

{"current_line": 0, "errorMsg": "", "cmdName": "get_program_info", "errorCode": "0", "programName": "test", "programState": "idle", "motion_line": 0}

Note:

  • current_line:The current line number of the main thread script being executed.
  • programName:The name of the program.
  • programState:The program state. idle. running. paused.
  • motion_line:The current line number of the motion instruction being executed (only for motion commands).

Robot Safety State

Protective Stop

Send message:

{"cmdName":"protective_stop_status"}

Receive message:

{"errorCode": "0", "errorMsg": "", "protective_stop": "0", "cmdName": "protective_stop_status"}

Note:

  • When the value of protective_stop is 1, it indicates that the robot is in a protective stop state. When the value is 0, it indicates the opposite. A protective stop usually occurs in the event of a collision with the robot. In such cases, the robot will enter the protective stop state.

Set Collision Sensitivity

Send message:

{"cmdName":"set_clsn_sensitivity","sensitivityVal":level}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_clsn_sensitivity"}

Note:

  • The values for level range from 0 to 5. A value of 0 means collision detection is turned off. Level 1 represents the highest collision sensitivity, at 25N. Level 5 represents the lowest collision sensitivity, at 125N, with a 25N difference between each level.

Get Collision Sensitivity

Send message:

{"cmdName":"get_clsn_sensitivity"}

Receive message:

{"errorCode": "0", "sensitivityLevel": 1, "cmdName": "get_clsn_sensitivity", "errorMsg": ""}

Note:

  • level The returned collision level.
    • 0 means collision detection is off.
    • 1 represents the highest collision sensitivity.
    • 5 represents the lowest collision sensitivity.

Recover from Collision Protection Mode after a Collision

Send message:

{"cmdName":"clear_error"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "clear_error"}

Robot Kinematics

Forward Kinematics

Send message:

{"cmdName":"kine_forward","jointPosition":[j1,j2,j3,j4,j5,j6]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "kine_forward", "cartPosition": [x,y,z,rx,ry,rz]}

Note:

  • [j1,j2,j3,j4,j5,j6] are the 6 joint angles that need to be sent for solving the forward kinematics. [x,y,z,rx,ry,rz] are the end-effector pose obtained after solving the forward kinematics.
  • The default forward and inverse kinematics interfaces are calculated in the current user coordinate system and tool coordinate system.

Inverse Kinematics

Send message:

{"cmdName":"kine_inverse","jointPosition":[j1,j2,j3,j4,j5,j6],"cartPosition": [x,y,z,rx,ry,rz]} 

Receive message:

  • If success:
{"errorCode": "0", "errorMsg": "", "cmdName": "kine_inverse", "jointPosition":[x,y,z,rx,ry,rz]}
  • If failed:
{"errorCode": "2", "errorMsg": "call kine_inverse failed", "cmdName": "kine_inverse"}

Note:

  • The jointPosition sent is the robot's reference joint angles. It is recommended that the user selects the robot's current joint angles as the reference joint angles. The unit is degrees.
  • The cartPosition sent is the robot's end-effector pose, represented as [x,y,z,a,b,c];
    • x, y, z are the positions in Cartesian space, with units in millimeters.
    • a, b, c are the orientations in space, with units in degrees.
  • The jointPosition received in the message is the robot's joint angles after solving the inverse kinematics.

Trajectory

Set Trajectory Parameters

Send message:

{"cmdName":"set_traj_config","acc":100,"vel":20,"xyz_interval":0.1,"rpy_interval":0.1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_traj_config"}

Note:

  • acc:The acceleration of the trajectory execution in mm/s².
  • vel:The velocity of the trajectory execution in mm/s.
  • xyz_interval:The data collection interval for Cartesian space displacement.
  • rpy_interval:The data collection interval for Cartesian space rotation.

Get Trajectory Parameters

Send message:

{"cmdName":"get_traj_config"}

Receive message:

{"acc": 100.0, "xyz_interval": 0.1, "errorMsg": "", "cmdName": "get_traj_config", "errorCode": "0", "rpy_interval": 0.1, "vel": 20.0}

Note:

  • acc:The acceleration of the trajectory execution in mm/s².
  • vel:The velocity of the trajectory execution in mm/s.
  • xyz_interval:The data collection interval for Cartesian space displacement.
  • rpy_interval:The data collection interval for Cartesian space rotation.

Set Trajectory Sample Mode

Send message:

{"cmdName":"set_traj_sample_mode","mode":1,"filename":"test"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_traj_sample_mode"}

Note:

  • mode: 0 means off, 1 means on.
  • filename:filename.

Get Trajectory Sample Mode Status

Send message:

{"cmdName":"get_traj_sample_status"}

Receive message:

{"sampleStatus": 1, "errorCode": "0", "cmdName": "get_traj_sample_status", "errorMsg": ""}

Note:

  • sampleStatus:0 means off, 1 means on.

Get Existed Trajectory File Name

Send message:

{"cmdName":"get_exist_traj_file_name"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_exist_traj_file_name", "trajTrackFileName": ["pythonTrack1", "test"]}

Note:

  • trajTrackFileName:The trajectory data file names are returned as a list of all the names.

Rename the Existed Trajectory File

Send message:

{"cmdName":"rename_traj_file_name","src":"test","dest":"test_rename"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "rename_traj_file_name"}

Note:

  • src:Source trajectory data file name.
  • dest:The modified file name.

Delete Trajectory File

Send message:

{"cmdName":"remove_traj_file","fileName":fileName}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "remove_traj_file"}

Note:

  • filename:filename

Generate Trajectory Execution Script

Send message:

{"cmdName":"generate_traj_exe_file","fileName":"test_rename"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "generate_traj_exe_file"}

Note:

  • filename:filename.

Force Control

For better understanding of the content below and the use of related functions, we suggest our users to read User Manual for Force Control Productsopen in new window and (Click to download quick start). Also, in this chapter, force control refers to force compliant control. End force sensor, Force sensor or Sensor refers to the 1/6 dimensions force/torque sensor mounted at the end of the robot.

Set Torque Sensor Brand Mode

Send message:

{"cmdName":"set_torsenosr_brand","sensor_brand":num}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torsenosr_brand"}

Note:

  • num: Represents the sensor model, with a value range of 1-6 or 10. It must match the model number engraved on the sensor's hardware casing. The value 10 specifically refers to sensors embedded within the robot flange. These embedded sensors are automatically managed by the system and do not require configuration through this interface.

Get Torque Sensor Brand Mode

Send message:

{"cmdName":"get_torsenosr_brand"}

Receive message:

{"sensor_brand": 1, "errorCode": "0", "cmdName": "get_torsenosr_brand", "errorMsg": ""}

Note:

sensor_brand: sensor mode

Start to Identify Sensor's End Payload

Send message:

{"cmdName":"start_torq_sensor_payload_identify","jointPosition":[j1,j2,j3,j4,j5,j6]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "start_torq_sensor_payload_identify"}

Note:

Get Sensor's End Payload Identifying Status

Send message:

{"cmdName":"get_torq_sensor_identify_staus"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_torq_sensor_identify_staus", "identify_status": 1}

Note:

  • identify_status:0 means complited with results ready to be read, 1 means in process, 2 means failed.

Get Sensor's End Payload Identifying Result

Send message:

{"cmdName":"get_torq_sensor_payload_identify_result"}

Receive message:

{"errorCode": "0", "centroid": [0, 0, 0], "mass": 0, "cmdName": "get_torq_sensor_payload_identify_result", "errorMsg": ""}

Note:

  • mass: The mass of the load, in kilograms (KG).
  • centroid: The centroid of the load, in millimeters (mm).

Please note:

Do carefully distinguish between set_tool_payload and set_payload:

payload affects the robot's dynamics.

tool_payload affects the force control performance (i.e., the robot's torque compensation during force control).

Set End Sensor Payload

Send message:

{"cmdName":"set_tool_payload","mass":weight,"centroid":[x,y,z]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tool_payload"}

Note:

  • mass: The mass of the load, in kilograms (KG).
  • centroid: The centroid of the load, in millimeters (mm).

For example, to set the load mass to 1 KG and the centroid to [10,10,10], you can send the command:

{"cmdName":"set_tool_payload","mass":1,"centroid":[10,10,10]}

Get End Sensor Payload

Send message:

{"cmdName":"get_tool_payload"}

Receive message:

{"errorCode": "0", "centroid": [0.0, 0.0, 0.0], "mass": 1.0, "cmdName": "get_tool_payload", "errorMsg": ""}

Note:

  • mass: The mass of the load, in kilograms (KG).
  • centroid: The centroid of the load, in millimeters (mm).

Set Force Control's Coordinate System

Send message:

{"cmdName":"set_ft_ctrl_frame", "ftFrame":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_ft_ctrl_frame"}

Note:

  • FtFrame: 0 means tool coordinate system; 1 means world coordinate system.

Get Force Control's Coordinate System

Send message:

{"cmdName":"get_ft_ctrl_frame"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_ft_ctrl_frame", "ftFrame":0}

Note:

  • FtFrame: 0 means tool coordinate system; 1 means world coordinate system.

Set Admittance Control Parameters

Send message:

{"cmdName":"set_admit_ctrl_config","axis":2,"opt":1,"ftUser":25,"ftConstant":5,"ftNnormalTrack":0,"ftReboundFK":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_admit_ctrl_config"}

Note:

  • axis:

    • 0 – X axis;
    • 1 – Y axis;
    • 2 – Z axis;
    • 3 – RX (rotation around X);
    • 4 – RY (rotation around Y);
    • 5 – RZ (rotation around Z).
  • opt:0 for off, 1 for on.

  • ftUser:Damping force, affecting the stiffness exhibited by the robot end-effector when interacting with the external environment. The larger this parameter, the greater the stiffness exhibited by the robot end-effector. The units are ×8 N·s/m (for x/y/z) and ×16 Nm·s/π (for rx/ry/rz).

  • ftReboundFK:Rebound force, representing the elastic coefficient between the robot's command trajectory (or initial position) and its position during compliance control. The units are N/mm (for x/y/z) and Nm/rad (for rx/ry/rz).

  • ftConstant:The target force, with units of N (for x/y/z) and Nm (for rx/ry/rz).

  • ftNnormalTrack:Interfaces for compatibility, must be set to 0 to ensure proper functioning.

  • Users can refer to User Manual for Force Control Productsopen in new window and (Click to download quick start) for detailed descriptions on above parameters.

Get Admittance Control Parameters

Send message:

{"cmdName":"get_admit_ctrl_config"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_admit_ctrl_config", "admitConfig": [[0, 5.0, 0.0, 0.0, 0], [0, 5.0, 0.0, 0.0, 0], [1, 25.0, 0.0, 5.0, 0], [0, 0.20000000298023224, 0.0, 0.0, 0], [0, 0.20000000298023224, 0.0, 0.0, 0], [0, 0.20000000298023224, 0.0, 0.0, 0]]}

Note:

  • admitConfig:There are 6 sets of 1×5 matrices, each representing the force control compliance parameters for x, y, z, rx, ry, and rz.

  • Each matrix contains values in sequence: [opt,ftUser,ftReboundFK,ftConstant,ftNnormalTrack]。

Turn On/Off End Sensor

Send message:

{"cmdName":"set_torque_sensor_mode","sensor_mode":mode}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torque_sensor_mode"}

Note:

  • mode:0 means off, 1 means on.

Turn On/Off Admittance Control

Send message:

{"cmdName":"enable_admittance_ctrl","enable_flag":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "enable_admittance_ctrl"}

Note:

enable_flag:0 means off, 1 means on.

Note:

This interface is depracated, and should be replaced by enable_tool_drive

Turn On/Off Tool Drive

It's function is consistent with enable_admittance_ctrl. The sensor needs to be activated and appropriate compliance control parameters should be set. Additionally, it is recommended to perform at least one force sensor zero calibration before enabling tool drive.

Send message:

{"cmdName":"enable_tool_drive", "enable_flag":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "enable_tool_drive"}

Note:

enable_flag:0 means off, 1 means on.

Get the Force Control Type and Initialization State

Send message:

{"cmdName":"get_compliant_type"}

Receive message:

{"errorCode": "0", "errorMsg": "", "compliance_type": 0, "sensor_compensation": 1, "cmdName": "get_compliant_type"}

Note:

  • sensor_compensation:1 indicates that the real-time force curve is displayed on the app, and the values returned from port 10000 for torqsensor[1][2] represent the actual external force. 0 means that when not in force control mode, the real-time force curve on the app shows the raw sensor readings, and the values returned from port 10000 for torqsensor[1][2] are the raw sensor readings (if in force control mode, they still represent the actual external force).
  • compliance_type:0 means not using any kind of compliance control method, 1 means using constant compliance control, and 2 means using speed compliance control.

Set Force Control Type and Zero Calibration (Initialization) Settings

Send message:

{"cmdName":"set_compliant_type","sensor_compensation":1,"compliance_type":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_compliant_type"}

Note:

  • sensor_compensation: 1 indicates that a sensor zero calibration will be performed immediately, and the real-time force curve on the app as well as the values returned from port 10000 for torqsensor[1][2] will switch to represent the actual external force. 0 means no calibration will be performed, and when not in force control mode, the real-time force curve on the app and the values returned from port 10000 for torqsensor[1][2] will switch to the raw sensor readings (if in force control mode, they will still represent the actual external force).
  • compliance_type: The force control type. 0 means not using any kind of compliance control method, 1 means using constant compliance control, and 2 means using speed compliance control.

Please note:

This interface is about to be deprecated, please use enable_cst_force_ctrl instead.

Get End Torque Sensor Status

Send message:

{"cmdName":"get_torque_sensor_mode"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_torque_sensor_mode", "sensor_mode": 0}

Note:

  • sensor_mode: 0 means off, 1 means on.

Set End Torque Sensor IP Adress

Send message:

{"cmdName":"set_torque_sensor_comm","type":0,"ip_addr":"172.30.1.110","port":55555}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torque_sensor_comm"}

Note:

  • type:0 for using network port or USB, 1 for using TIO.
  • ip_addr: The address of the force control sensor when using network port.
  • port: The port number of the force control sensor when using network port.
  • ip_addr and port don't take effect when setting to 1 or using a USB. Setting as the sample does will do fine.

Get End Torque Sensor Communication Parameters

Send message:

{"cmdName":"get_torque_sensor_comm"}

Receive message:

{"ip_addr": "192.168.2.228", "errorMsg": "", "cmdName": "get_torque_sensor_comm", "errorCode": "0", "type": 0, "port": 49152}

Note:

  • type:0 for using network port or USB, 1 for using TIO.
  • ip_addr: The address of the force control sensor when using network port.
  • port: The port number of the force control sensor when using network port.
  • ip_addr and port are invalid paramters when using TIO or USB, and the return value is invalid too.

Set Cutoff Frenquency of the Torque Sensor Low-pass Filter

Send message:

{"cmdName":"set_torque_sensor_filter","torqueSensorFilter":10}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torque_sensor_filter"}

Note:

  • torqueSensorFilter:The cutoff frequency of the low-pass filter. Unit: Hz.

Get Cutoff Frenquency of the Torque Sensor Low-pass Filter

Send message:

{"cmdName":"get_torque_sensor_filter"}

Receive message:

{"errorCode": "0", "errorMsg": "", "torqueSensorFilter": 1.0, "cmdName": "get_torque_sensor_filter"}

Note:

  • torqueSensorFilter:The cutoff frequency of the low-pass filter. Unit: Hz.

Disable Force Control

Send message:

{"cmdName":"disable_force_control"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "disable_force_control"}

Set Velocity Compliant Control Parameters

Please note:

This interface is about to be deprecated.

Send message:

{"cmdName":"set_vel_compliant_ctrl","compliant_ctrl":[vc_level, rate1, rate2, rate3, rate4]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_vel_compliant_ctrl"}

Note:

  • compliant_ctrl:vc_level speed compliance control level.
  • rate1; rate2; rate3; rate4.

Set Compliant Control Condition

Send message:

{"cmdName":"set_compliance_condition","compliant_condition":[0,0,0,0,0,0]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_compliance_condition"}

Note:

  • compliant_condition:Force and torque components of the force sensor.
    • fx The force component along the x-axis.
    • tx The torque component around the x-axis.

Set End Torque Sensor Soft Limit

Send message:

{"cmdName":"set_torque_sensor_soft_limit","torqueSensorSoftLimit":{"Fx":1,"Fy":1,"Fz":1,"Mx":1,"My":1,"Mz":1}}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torque_sensor_soft_limit"}

Note:

  • "Fx","Fy","Fz","Mx","My","Mz" represent the maximum allowed force or torque values in each direction, with units of N (for force) and Nm (for torque). Exceeding these values will trigger an error, terminate the program, and stop the robot's movement.

Get End Torque Sensor Soft Limit

Send message:

{"cmdName":"get_torque_sensor_soft_limit"}

Receive message:

{"errorCode": "0", "errorMsg": "", "torqueSensorSoftLimit": {"Fx": 1.0, "Fy": 1.0, "Fz": 1.0, "My": 1.0, "Mx": 1.0, "Mz": 1.0}, "cmdName": "get_torque_sensor_soft_limit"}

Note:

  • "Fx","Fy","Fz","Mx","My","Mz" represent the maximum allowed force or torque values in each direction, with units of N (for force) and Nm (for torque). Exceeding these values will trigger an error, terminate the program, and stop the robot's movement.

Set Torque Reference Point

Send message:

{"cmdName":"set_torque_ref_point", "ref_point":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_torque_ref_point"}

Note:

  • ref_point:0 means the center of torque sensor, 1 means TCP.

Get Torque Reference Point

Send message:

{"cmdName":"get_torque_ref_point"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_torque_ref_point"}

Note:

  • ref_point:0 means the center of torque sensor, 1 means TCP.

Set End Sensor Sensitivity Threshold

Send message:

{"cmdName":"set_end_sensor_sensitivity_threshold", "threshold_percent":[0.3, 0.3, 0.3, 0.3, 0.3, 0.3]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_torque_ref_point"}

Note:

  • threshold_percent: A 6-dimensional array, with values ranging from 0 to 1. The higher the value, the less sensitive the sensor.

Get End Sensor Sensitivity Threshold

Send message:

{"cmdName":"get_end_sensor_sensitivity_threshold"}

Receive message:

{"threshold": [30.5, 1.6250000000000002], "errorCode": "0", "cmdName": "get_end_sensor_sensitivity_threshold", "threshold_percent": [0.3, 0.3, 0.3, 0.3, 0.3, 0.3], "errorMsg": ""}

Note:

  • threshold_percent: A 6-dimensional array, with values ranging from 0 to 1. The higher the value, the less sensitive the sensor.
  • threshold: A 2-dimensional array, representing the actual threshold values.

Set Fusion Drive Sensitivity Level

Send message:

{"cmdName":"set_fusion_drive_sensitivity_level", "sensitivity_level":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_fusion_drive_sensitivity_level"}

Note:

  • sensitivity_level 0-5, 0 means off.

Get Fusion Drive Sensitivity Level

Send message:

{"cmdName":"get_fusion_drive_sensitivity_level"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_fusion_drive_sensitivity_level", "sensitivity_level": 0}

Note:

  • sensitivity_level 0-5, 0 means off.

Set Motion Limit (Singularity and Joint Limit) Warning Range

Send message:

{"cmdName":"set_motion_limit_warning_range", "range_level":1}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_motion_limit_warning_range"}

Note:

  • range_level:1-5

Get Motion Limit (Singularity and Joint Limit) Warning Range

Send message:

{"cmdName":"get_motion_limit_warning_range"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_motion_limit_warning_range", "range_level":1}

Note:

  • range_level:1-5

Get Torque Sensor Data

Send message:

{"cmdName":"get_torque_sensor_data","type":1}

Receive message:

{"status": 0, "errorMsg": "", "errcode": 0, "cmdName": "get_torque_sensor_data", "errorCode": "0", "data": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}

Note:

  • type:1 or 2 or 3
  • data: Actual values from the torque sensor, a 6-dimensional array.
  • status: Whether the sensor is enabled. 0 for not enabled, 1 for enabled.

Zero Calibration of End Sensor

Send message:

{"cmdName":"zero_end_sensor"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "zero_end_sensor"}

Note:

  • After zero calibration, the sensor's force curve should return to a value near 0.

Set Force Stop Condition

Send message:

{"cmdName":"set_force_stop_condition", "opt":[0, 1, 1, 0, 0, 0], "lowerlimiton":[0, 1, 1, 0, 0, 0], "lowerlimit":[3.0, 4.0, 5.0, 6.0, 7.0, 8.0], "upperlimiton":[0, 1, 1, 0, 0, 0], "upperlimit":[13.0, 14.0, 15.0, 16.0, 17.0, 18.0]}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_force_stop_condition"}

Note:

  • opt A 6-dimensional array representing whether force control termination conditions are enabled for each of the 6 dimensions. 0 means not enabled, any non-zero value means enabled.
  • lowerlimiton A 6-dimensional array where 0 means no lower limit is set, and any non-zero value means a lower limit is set.
  • lowerlimit A 6-dimensional array representing the lower limit values.
  • upperlimiton A 6-dimensional array where 0 means no upper limit is set, and any non-zero value means an upper limit is set.
  • upperlimit A 6-dimensional array representing the upper limit values.

Set Compliant Speed Limit

Send message:

{"cmdName":"set_compliant_speed_limit", "speed_limit":10.0, "angular_speed_limit":10.0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_compliant_speed_limit"}

Note:

  • speed_limit:Speed limti, mm/s
  • angular_speed_limit:Angular speed limit, deg/s

Get Compliant Speed Limit

Send message:

{"cmdName":"get_compliant_speed_limit"}

Receive message:

{"errorCode": "0", "angular_speed_limit": 10.0, "cmdName": "get_approach_speed_limit", "speed_limit": 10.0, "errorMsg": ""}

Note:

  • speed_limit:Speed limti, mm/s
  • angular_speed_limit:Angular speed limit, deg/s

Set Force Control Rigidity Parameters

Send message:

{"cmdName":"set_tool_drive_config", "axis":0, "opt":1, "rigidity":0.0, "rebound": 100.0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tool_drive_config"}

Note:

  • axis Represents which axis is configured. The optional values are 0 to 5 for compliance directions, corresponding to fx, fy, fz, mx, my, mz.
  • opt 0 means not selected, and any non-zero value means selected.
  • rigidity A range from 0 to 1. The higher the value, the stiffer the drag.
  • rebound Rebound force, representing the strength of the robotic arm's elastic return to the initial position.

Get Tool Drive Parameters

Send message:

{"cmdName":"get_tool_drive_config"}

Receive message:

{"errorCode": "0", "force_ctrl_config": [[1, 0.0, 100.0], [1, 0.30000001192092896, 0.0], [1, 0.30000001192092896, 0.0], [1, 0.30000001192092896, 0.0], [1, 0.30000001192092896, 0.0], [1, 0.30000001192092896, 0.0]], "cmdName": "get_tool_drive_config", "errorMsg": ""}

Note:

  • force_ctrl_config:Returns a list containing six list elements, each representing one of the six axes. Each list contains three elements that represent the following:
    • opt 0 means not selected, and any non-zero value means selected.
    • rigidity A range from 0 to 1. The higher the value, the stiffer the drag.
    • rebound Rebound force, representing the strength of the robotic arm's elastic return to the initial position.

Enable Constant Force Control

Send message:

{"cmdName":"enable_cst_force_ctrl", "enable_flag":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "enable_cst_force_ctrl"}

Note:

  • enable_flag: 0 means off, 1 means on.

Set Constant Force Control

Send message:

{"cmdName":"set_cst_force_ctrl_config", "axis":0, "opt":1, "ftDamping":10.0, "ftConstant":10.0,"ftReboundFK":10.0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_cst_force_ctrl_config"}

Note:

  • axis Specifies which axis is configured. Optional values are 0 to 5 for compliance directions, corresponding to fx, fy, fz, mx, my, and mz.
  • opt 0 means not selected, and any non-zero value means selected.
  • ftDamping Damping force, indicating the stiffness of the robot during the force control process.
  • ftConstant Represents the target force.
  • ftReboundFK Rebound force, indicating the strength of the robotic arm's elastic return to the command trajectory.

Get Constant Force Control

Send message:

{"cmdName":"get_cst_force_ctrl_config"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_cst_force_ctrl_config"}

Note:

  • axis Specifies which axis is configured. Optional values are 0 to 5 for compliance directions, corresponding to fx, fy, fz, mx, my, and mz.
  • opt 0 means not selected, and any non-zero value means selected.
  • ftDamping Damping force, indicating the stiffness of the robot during the force control process.
  • ftConstant Represents the target force.
  • ftReboundFK Rebound force, indicating the strength of the robotic arm's elastic return to the command trajectory.

Set Constant Force Control Coordinate System

Send message:

{"cmdName":"set_cst_force_ctrl_frame", "cstForceFrame":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_cst_force_ctrl_frame"}

Note:

  • cstForceFrame:0 means tool coordinate system; 1 means world coordinate system.

Get Constant Force Control Coordinate System

Send message:

{"cmdName":"get_cst_force_ctrl_frame"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_cst_force_ctrl_frame"}

Note:

  • cstForceFrame: 0 means tool coordinate system; 1 means world coordinate system.

Set Tool Drive Coordinate System

Send message:

{"cmdName":"set_tool_drive_frame", "toolDragFrame":0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_tool_drive_frame"}

Note:

  • toolDragFrame:0 means tool coordinate system; 1 means world coordinate system.

Get Tool Drive Coordinate System

Send message:

{"cmdName":"get_tool_drive_frame"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "get_tool_drive_frame", "toolDragFrame": 0}

Note:

  • toolDragFrame:0 means tool coordinate system; 1 means world coordinate system.

Set Constant Force Control Tolerance

Send message:

{"cmdName":"set_cst_force_ctrl_tol", "force_tol":10.0, "torque_tol":10.0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_cst_force_ctrl_tol"}

Note:

  • force_tol:Force tolerance
  • torque_tol:Torque tolerance

Get Constant Force Control Tolerance

Send message:

{"cmdName":"get_approach_speed_limit"}

Receive message:

{"errorCode": "0", "angular_speed_limit": 10.0, "cmdName": "get_approach_speed_limit", "speed_limit": 10.0, "errorMsg": ""}

Note:

  • force_tol:Force tolerance
  • torque_tol:Torque tolerance

Set Approach Speed Limit

Send message:

{"cmdName":"set_approach_speed_limit", "speed_limit":10.0, "angular_speed_limit":10.0}

Receive message:

{"errorCode": "0", "errorMsg": "", "cmdName": "set_approach_speed_limit"}

Note:

  • speed_limit:Speed limit, mm/s
  • angular_speed_limit:Angular speed, deg/s

Get Approach Speed Limit

Send message:

{"cmdName":"get_approach_speed_limit"}

Receive message:

{"errorCode": "0", "angular_speed_limit": 10.0, "cmdName": "get_approach_speed_limit", "speed_limit": 10.0, "errorMsg": ""}

Note:

  • speed_limit:Speed limit, mm/s
  • angular_speed_limit:Angular speed, deg/s

Get Tool Drive Status

Send message:

{"cmdName":"get_tool_drive_stat"}

Receive message:

{"errorCode": "0", "errorMsg": "", "enable_flag": 0, "cmdName": "get_tool_drive_stat", "drive_stat": 0}

Note:

  • enable_flag:0 means disable force control drag enable, and 1 means enable it.
  • drive_stat:Represents the current state of the drag, indicating whether warnings for singularity, speed, or joint limits have been triggered.

Get Constant Force Control Status

Send message:

{"cmdName":"get_cst_force_ctrl_stat"}

Receive message:

{"errorCode": "0", "errorMsg": "", "cst_force_ctrl_stat": 0, "cmdName": "get_cst_force_ctrl_stat"}

Note:

  • cst_force_ctrl_stat: 0 means not enabled, 1 means enabled, and 2 means speed mode (compatibility mode; this option will not be available in newer versions).

Troubleshooting

Methods

If you encounter issues when using JAKA TCP/IP control protocol, please follow these steps for troubleshooting:

  • Ensure that the network connection between the client and the robot controller’s IP address is normal.
  • For exceptions in TCP/IP command calls, analyze the return values and error messages to identify the related issues.
  • Retrieve the robot system error code and error message from the feedback data of port 10000 to troubleshoot the relevant anomalies.
  • You can also connect via the robot app to check for system-related issues.

During the troubleshooting process, you can deploy network debugging tools or use Wireshark on the client side to analyze relevant data.

FAQ

  • In the actual development and testing process, if you encounter issues such as commands not returning, it is recommended to use a network debugging tool to connect to the robot server: the IP is the robot’s IP address, and the port number is either 10000 or 100001. This allows you to check whether the robot server is functioning properly. If it is, please verify if there is any error in your code.

  • During actual use, if you connect to port 10000 and notice that the received packets are incomplete, with only part of the data being received.

    • In this case, it is recommended to check the client socket's receive buffer size. The buffer might be set too small to handle the packet size returned from port 10000, causing the reception to be incomplete.
  • If there is an issue with the data push frequency being too low or delayed:

    • In this case, it is recommended to check the server’s port data refresh rate. Specifically, check the port10000_delay_ms in the optionalconfig section mentioned earlier to ensure it is set appropriately.

User Feedback

If you encounter any error messages or unclear descriptions in the document, or if you have any comments or suggestions, please send an email to support@jaka.com. We will respond to you as soon as possible.

Last update: