Development and Use Based on Communication Protocol Packets

Communication Settings

Ethernet TCP/IP

  • Bus Interface: Gigabit Ethernet Port
  • IP: Static IP: 192.168.0.232; For Wi-Fi or Dynamic IP, please refer to the Connection interface on the screen.
  • Port: 4500

    485 Modbus

  • Bus Interface: Bottom 485
  • Baud Rate: 115200
  • Data Bits: 8
  • Parity: None
  • Stop Bits: 1

Robotic arm motion and speed parameter table

Joints minimum angle(°) maximum angle(°) maximum speed(°/s) maximum acceleration(°/s²)
J1 -162 162 150 200
J2 -125 125 150 200
J3 -154 154 150 200
J4 -162 162 150 200
J5 -162 162 150 200
J6 -165 165 150 200
Coords minimum coord(mm) maximum coord(mm) maximum speed(mm/s) maximum acceleration(mm/s²)
x -466 466 200 400
y -466 466 200 400
z -150 677 200 400
rx/ry/rz -180° 180° 40°/s 66°/s²


Introduction to TCP/IP Commands for Network Interfaces

Send and Receive Format Both sending and receiving are represented in hexadecimal. Each command contains 5 parts, as shown below:

[Frame Header][Frame Header][Length][Function Code][Data][Checksum - High Byte][Checksum - Low Byte]

  1. Frame Header (2 bytes): 0xFE 0XFE
  2. Valid Length (1 byte): 3-N, length starts from the function code and ends with the checksum.
  3. Function Code (1 byte): 1-255
  4. Data Bits: 0-N, high byte first.
  5. Frame Trailer: crc16-modbus, high byte first.
  6. All commands have first-level receive feedback; position mode control has position feedback.

Basic Control

  1. Read Master Control Version Number
    Function Code: 02
    Send Data Bits: None
    Feedback Data Bits: Version Number - 1 byte, requires /10.0
    Send Command: FE FE 03 02 0D D1
    Feedback Command Example: FE FE 04 02 0A 51 7D, where the version number is V1.0

  2. Read End Version Number
    Function Code: 09
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Version Number, requires /10.0

  3. Start Robot
    Function Code: 0x10
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Startup Status, 0-2; 0 - Startup Failed, 1 - Startup Successful, 2 - Emergency Stop Triggered

  4. Shut down the robot
    Function code: 0x11
    Send data bits: None
    Feedback fixed data bits: Bytes 1-2: 0xFF 0x01
    Feedback command: FE FE 05 11 FF 01 E8 EC

  5. Read robot startup status
    Function code: 0x12
    Send data bits: None
    Feedback data bits: Byte 1: Startup status, 0-2; 0-Startup failed 1-Startup successful 2-Emergency stop triggered

  6. Read zero-position calibration status
    Function code: 0x5A
    Send data bits: None
    Feedback data bits: Byte 1: 0/1; Overall zero-position calibration status Bytes 2-7: 1X6 joint zero-position calibration status

  7. Switch Modbus communication
    Function code: 0x6A
    Send data bits: Byte 1: 0/1 1 - On, 0 - Off. Default is Off.
    Modbus Send Command: FE FE 04 6A 01 9D 92
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  8. Read Modbus Communication Status
    Function Code: 0x6B
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Status 0/1 1 - On, 0 - Off

Motion Control

  • Motion control speed range: 1-100, please refer to the above table of robotic arm motion and speed parameters for actual speed percentage.
  • Motion modes: Position interpolation, refresh interruption, torque; only position interpolation provides motion positioning feedback.
  • Position positioning feedback data: FE FE 04 5B Status CRC-High CRC-Low; Normal motion command: FE FE 04 5B 00 CD 46; Abnormal motion command - J6 over-limit: FE FE 04 5B 06 CF C6

  • Full joint angle control
    Function code: 0x22
    Send data bits: Bytes 1-12: 2X6 joint angle (angle * 100.0) Byte 13: Speed
    [90, 10, -90, 45, 80, -100], running speed 50%, send command: FE FE 10 22 23 28 03 E8 DC D8 11 94 1F 40 27 10 32 E3 57<br> First-level feedback fixed data bits: Bytes 1-2: 0xFF 0x01<br> Second-level position feedback: Only available in interpolation motion mode,FE FE 04 5B 00 CD 46`

  • Single joint angle control
    Function code: 0x21
    Send data bits: Byte 1: Joint; Bytes 2-3: Angle (angle * 100.0) Byte 4: Speed
    J1 moves to 50°, running speed 10%, send command: FE FE 07 21 01 13 88 0A 82 7A
    First-level feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Read All Joint Angles
    Function Code: 0x20
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-12: 2x6 Joint Angles (Angle/100.0)
    [90, 10, -90, 45, 80, -100] Feedback Command: FE FE 10 20 23 28 03 E8 DC D8 11 94 1F 40 27 10 32 21 54

  • Full Coordinate Control
    Function Code: 0x25
    Send Data Bits: Bytes 1-12: 2x6 Coordinates (XYZ10.0, RXRYRZ100.0) Byte 13: Speed
    First Layer Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Single coordinate control
    Function code: 0x24
    Send data bits: Byte 1: Coordinate axis; Bytes 2-3: Coordinate (XYZ10.0, RXRYRZ100.0) Byte 4: Velocity
    First layer feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Read full coordinates
    Function code: 0x23
    Send data bits: None
    Feedback data bits: Bytes 1-12: 2X6 coordinate (XYZ/10.0, RXRYRZ/100.0)

  • Read robot motion status
    Function code: 0x2B
    Send data bits: None
    Feedback data bits: Byte 1: Motion status 0/1, 0 - not moving; 1 - moving

  • Detecting if the robot has reached the designated point
    Code: 0x2A, Error accuracy within 1° angle, within 2mm coordinates
    Send Data Bits: Bytes 1-12: 26 joint angles/coordinates (angle 100.0, coordinates XYZ 10.0, RXRYRZ 100.0); Byte 13: Mode 1/2 1-Angle 2-Coordinate
    Feedback Data Bits: Byte 1: Position Status 0/1 0-Not in position, 1-In position

  • Motion Pause
    Function Code: 0x26
    Send Data Bits: None
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Motion Resumption
    Function Code: 0x28
    Send Data Bits: None
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Movement End
    Function Code: 0x29
    Send Data Bits: None
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Detect Movement Pause
    Function Code: 0x27
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Pause Status 0/1, 0 - Not Manually Paused; 1 - Paused

  • Continuous Joint Movement
    Function Code: 0x30
    Send Data Bits: Byte 1: Joint; Byte 2: Direction 0/1 0 - Reverse Rotation 1 - Forward Rotation Byte 3: Speed
    First Layer Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Continuous Coordinate Movement
    Function Code: 0x32
    Send Data Bits: Byte 1: Coordinate Axis; Byte 2: Direction 0/1 0 - Reverse Rotation 1-Forward Rotation Byte 3: Speed
    First-level feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • RPY Rotation
    Function Code: 0xF5
    Send Data Bits: Byte 1: Mode 1-3 1-Roll Angle 2-Pitch Angle 3-Yaw Angle; Byte 2: Direction 0/1 0-Reverse Rotation 1-Forward Rotation Byte 3: Speed
    First-level feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Joint Stepping Control
    Function Code: 0x33
    Send Data Bits: Byte 1: Joint; Bytes 2-3: Step Value * 100.0 Byte 3: Speed
    First-level feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Coordinate Stepping Control
    Function Code: 0x34
    Send Data Bits: Byte 1: Coordinate Axis; Bytes 2-3: Step Value (XYZ10.0, RXRYRZ100.0) Byte 4: Velocity
    First Layer Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Calculate Inverse Kinematics
    Function Code: 0x8D
    Send Data Bits: Bytes 1-12: Current Angle of 2x6 Joint Bytes 13-26: Target Coordinate Value of 2x6 Joint
    Feedback Data Bits: Bytes 1-24: Angle of 4x6 Joint (/100.0)

  • Start Drag Teaching
    Function Code: 0x70
    Send Data Bits: None
    Feedback Data Bits: 0xFF 0x01

  • Pause Sampling
    Function Code: 0x72
    Send Data Bits: None
    Feedback Data Bits: 0xFF 0x01

  • Execute Teaching Point
    Function Code: 0x71
    Send Data Bits: None
    Feedback Data Bits: 0xFF 0x01

  • Clear Sampling Point
    Function Code: 0x73
    Send Data Bits: None
    Feedback Data Bits: 0xFF 0x01

  • Query Collision Detection Mode
    Function Code: 0xFD
    Send Data Bits: None
    Feedback Data Bits: Byte 1: 0/1, 1-open 0-close

  • Set Collision Detection Mode
    Function Code: 0x74
    Send Data Bits: 1-open 0-close After enabling collision detection, the robotic arm will automatically stop if a collision lasting longer than 200ms and exceeding the collision threshold occurs during movement.
    Feedback Data Bits: 0xFF 0x01

  • Set Collision Threshold
    Function Code: 0x75
    Send Data Bits:
    Byte 1: joint range:(1-6)
    Byte 2: radio range:(50-250)%
    You can set the collision threshold for the joints. The default value is 100%. The smaller the value, the easier it is to trigger a collision.
    Feedback Data Bits: 0xFF 0x01

  • Get Collision Threshold
    Function Code: 0x76
    Send Data Bits: None
    Feedback Data Bits:
    Bytes 1-6: Collision threshold for all joints

  • Set Torque Compensation Coefficient
    Function Code: 0x77
    Send Data Bits:
    Byte 1: joint range:(1-6)
    Byte 2: radio range:(0-250)% Friction compensation coefficient for the torque ring. The default value is 0. The larger the coefficient, the easier it is to drag.
    Byte 3: Damping: 0-close 1-open Impedance switch, default is off. Turning it on increases damping; higher damping makes it harder to drive.
    Feedback data bits: 0xFF 0x01

  • Obtain Torque Compensation Coefficient
    Function Code: 0x78
    Send Data Bits: None
    Feedback Data Bits:
    Bytes 1-6: Full-Joint Torque Compensation Coefficient
    Bytes 7-12: Full-Joint Impedance Switch

  • Execute Dynamic Trajectory Identification
    Function Code: 0xF8
    Send Data Bits: Byte 1: rank (0-1), 0: Identify Trajectory, 1: Low-Speed ​​Identify Trajectory
    Feedback Data Bits: 0xFF 0x01
    Execute the trajectory identification, which takes 24 seconds. The movement is relatively large, so please pay attention to safety. Before use, you need to execute the low-speed trajectory using fourier_trajectories(1) to confirm the safe range. After the low-speed execution is completed, execute the normal speed fourier_trajectories(0).

  • Dynamic parameter identification
    Function code: 0x97
    Send data bits: None
    Feedback data bits: 0xFF 0x01
    One-click identification requires first executing the dynamic trajectory identification to generate the identify_data.log file. The identification takes five minutes. After the identification is completed, the identification accuracy will be automatically calculated. If the accuracy meets the standard, it will be automatically written to the dynamic_paremeters.log file.

  • Circular Trajectory Motion
    Function Code: 0x8C
    Send Data Bits:
    Circular Trajectory Points (transpoint) Circular End Points (endpoint)
    Bytes 1-2: transpoint.x (10) Bytes 13-14: endpoint.x (10)
    Byte 25: speed (1-100)
    Bytes 3-4: transpoint.y Bytes 15-16: endpoint.y
    Bytes 5-6: transpoint.z Bytes 17-18: endpoint.z
    Bytes 7-8: transpoint.rx (100)
    Bytes 19-20: endpoint.rx (
    100)
    Bytes 9-10: transpoint.ry Bytes 21-22: endpoint.ry
    Bytes 11-12: transpoint.rz Bytes 23-24: endpoint.rz
    Feedback data bits: 0xFF 0x01
    Based on the current position of the robotic arm (starting point), the given arc transit point (transpoint), and the arc ending point (endpoint), an arc is determined by these three points, causing the robotic arm to execute the arc trajectory in the order of starting point, transit point, and ending point.

  • Set Motion Mode

  • This interface takes a relatively long time to execute, approximately 4ms.
    Function code: 0x16
    Send data bits: Byte 1: Mode 0/1 0-Position 1-Refresh, the robot intelligently uses refresh mode; default is position mode.
    Feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Read Motion Mode
    Function code: 0x17
    Send data bits: None
    Feedback data bits: Byte 1: Mode 0/1 0-Position 1-Refresh

  • Set Motion Control Mode

  • This interface takes a relatively long time to execute, approximately 4ms.
    Function Code: 0x1E
    Send Data Bits: Byte 1: Mode 0/1 0-Position 1-Torque, zero-force drag; Default position mode
    Feedback Data Bits: Byte 1: 0xFF, Byte 2: 0/1 0-Setting failure, incorrect parameters; 1-Parameter correct

  • Read Motion Control Mode
    Function Code: 0x1F
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Mode 0/1 0-Position 1-Torque, zero-force drag

  • Over-limit Return to Zero

  • After exceeding the limit, manual movement back to the limit is not required; currently only supported in position mode, not in refresh mode control.
    Function Code: 04
    Send Data Bits: None
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

Auxiliary Functions

Configuration

  • Zero position setting is required after system update before movement.
  • Setting Zero Position
    Function Code: 0x54
    Send Data Bits: Byte 1: Joint
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Setting Robot Torque Status
    Function Code: 0x13
    Send Data Bits: Byte 1: Joints 1-6 254-All; Byte 2: Mode 0/1 0-Disabled 1-Enabled; Movement is only possible when enabled
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Setting RGB Color
    Function Code: 0x0C
    Send Data Bits: Bytes 1-3: R, G, B Range 0-255, All 0s-Lights off
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Set Maximum Speed
    Function Code: 0x41
    Send Data Bits: Byte 1: Mode 0/1 0-Angle 1-Coordinate Bytes 2-3: Speed, set only within the maximum range
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Set Maximum Acceleration
    Function Code: 0x43
    Send Data Bits: Byte 1: Mode 0/1 0-Angle 1-Coordinate Bytes 2-3: Acceleration, set only within the maximum range
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Read Maximum Speed
    Function Code: 0x40
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-2: Speed

  • Read Maximum Acceleration
    Function Code: 0x42
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-2: Acceleration

  • Set Joint Minimum Angle
    Function Code: 0x4c
    Send Data Bits: Byte 1: Joint Bytes 2-3: Minimum Angle * 10.0; Can only be set within the default range, no error will occur upon power failure
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  • Read Joint Minimum Angle
    Function Code: 0x4a
    Send Data Bits: Byte 1: Joint
    Feedback Data Bits: Bytes 1-2: Minimum Angle / 10.0

  • Set Joint Maximum Angle
    Function Code: 0x4d
    Send Data Bits: Byte 1: Joint Bytes 2-3: Maximum angle * 10.0; can only be set within the default range, no error will occur upon power failure.
    Feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Read the maximum angle of the joint
    Function code: 0x4b
    Send data bits: Byte 1: Joint
    Feedback data bits: Bytes 1-2: Maximum angle / 10.0

  • Set the joint direction

  • Pls move to zero position,then read the current direction first, latest set it
    Function code: 0x7D
    Send data bits: Byte 1: Joint Byte 2: Direction 0/1 1-Same direction 0-Opposite direction
    Feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  • Read Joint Direction
    Function Code: 0x7C
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-6: 1x6 Joint Direction

  • Read VR Mode
    Function Code: 0x79
    Send Data Bits: None
    Feedback Data Bits: Byte: 1-open 0-close
    Enabling VR mode reduces the motion command buffer length from 80 to 2. Suitable for development scenarios where motion buffer accumulation is undesirable, such as VR control and remote control.

  • Set VR Mode
    Function Code: 0x7a
    Send Data Bits: Byte: 1-open 0-close
    Feedback Data Bits: 0xFF 0x01

  • Set Free Movement Status

  • Off by default. When enabled, the robotic arm can be manually rotated by pressing and holding the end button for 1 second.
    Function Code: 0x1A
    Send Data Bits: Byte 1: 1-open 0-close
    Feedback Data Bits: 0xFF 0x01

  • Read Free Movement Status
    Function Code: 0x1B
    Send Data Bits: None
    Feedback Data Bits: Byte 1: 1-open 0-close

IO Control

Bottom IO
  1. Set Base IO Output
    Function Code: 0xA0
    Transmit Data Bits: Byte 1: Pin Number 1-12 Byte 2: Status 0/1 0 - Low 1 - High
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  2. Read Base IO Input
    Function Code: 0xA1
    Transmit Data Bits: Byte 1: Pin Number 1-12
    Feedback Data Bits: Byte 1: Status 0/1 0 - Low 1 - High

End IO
  1. Set End IO Output
    Function Code: 0x61
    Transmit Data Bits: Byte 1: Pin Number 1/2 Byte 2: Status 0/1 0 - Low 1 - High
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  2. Read all pin statuses at the end
    Function code: 0x7B
    Transmit data bits: None
    Feedback data bits: Byte 1: Input 1 status 0/1 0-low level 1-high level; Byte 2: Input 2 status; Byte 3: End button 1 status; Byte 4: End button 2 status

External 485/CAN communication device control

  1. Bottom external device configuration
    Function code: 0x65
    Transmit data bits: Byte 1: Mode 1/2 1-485 device 2-CAN device; Bytes 2-5: Baud rate; Bytes 6-9: Timeout
    Feedback fixed data bits: Bytes 1-2: 0xFF 0x01

  2. Read bottom external device configuration
    Function code: 0x67
    Transmit data bits: None
    Feedback data bits: Byte 1: Mode 1/2 1-485 device; 2-CAN device; Bytes 2-5: Baud rate; Bytes 6-9: Timeout

  3. Bottom External Device Control
    Function Code: 0x66
    Send Data Bits: CAN Device: Bytes 1-4: CAN_id; Bytes 5-N: CAN data, maximum 8; 485 Device: 1-N: 485 data, maximum 100
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  4. End 485 External Device Control
    Function Code: 0xB5
    Send Data Bits: Bytes 1-N: 485 data, maximum 45
    Feedback Data Bits: Bytes 1-N: 485 data returned by the device

  5. Set Terminator 485 Baud Rate

  6. Default 115200
    Function Code: 0xB8
    Send Data Bits: Bytes 1-4: Baud Rate
    Feedback Data Bits: 0xFF 0x01

  7. Set Terminator 485 Timeout

  8. Default 10s
    Function Code: 0xB9
    Send Data Bits: Bytes 1-2: Timeout, Unit: ms, Range: 1-10s
    Feedback Data Bits: 0xFF 0x01

  9. Read Terminator 485 Baud Rate Timeout
    Function Code: 0xBA
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-4: Baud Rate, Bytes 5-6: Timeout

Status Query

  1. Read Robot Status
    Function Code: 0xA2
    Send Data Bits: None
    Feedback Data Bits: Byte 1: Collision Detection Status 0/1 1-Collision; Byte 2: Movement Status 0/1 1-In Motion; Bytes 3-8: 1x6 Joint Exceeding Limits 0/1 1-Exceeding Limits; Bytes 9-20: 2x6 Joint Motor Errors 0-Normal >0 Abnormal; Bytes 21-32: 2x6 Joint Motor Software Errors 0-Normal >0 Abnormal; See error messages and position feedback table for details.

  2. Read Motion Error Information
    Function Code: 0x07
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-2: Error Messages, see error messages and position feedback table for details.

  3. Read Joint Communication Error Count
    Function Code: 0xA3
    Send Data Bits: Byte 1: Joints 1-6
    Feedback Data Bits: Bytes 1-2: Joint Send Error Count 0-32700; Bytes 3-4: Joint Read Error Count 0-32700; Bytes 5-6: Endpoint Send Error Count 0-32700; Bytes 7-8: Endpoint Read Error Count 0-32700

  4. Read Joint Running Speed
    Function Code: 0xE1
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-12: 2x6 Running Speed ​​/ 100.0 0-30rpm

  5. Get Joint Current
    Function Code: 0xE2
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-12: 2x6 Joint Current Unit: MA

Set Coordinate System

  1. Set Tool Coordinate System
    Function Code: 0x81
    Send Data Bits:
    Bytes 1-2: x (±1000) (10xmm)
    Bytes 3-4: y (±1000)
    Bytes 5-6: z (±1000)
    Bytes 7-8: rx (±180) (100xDeg)
    Bytes 9-10: ry (±180)
    Bytes 11-12: rz (±180)
    Feedback Data Bits: 0xFF 0x01

  2. Read Tool Coordinate System
    Function Code: 0x82
    Send Data Bits: None
    Feedback Data Bits:
    Bytes 1-2: x (±1000) (10xmm)
    Bytes 3-4: y(±1000)
    Bytes 5-6: z (±1000)
    Bytes 7-8: rx (±180) (100xDeg)
    Bytes 9-10: ry (±180)
    Bytes 11-12: rz (±180)

  3. Set World Coordinate System
    Function Code: 0x83
    Data Bits Sent:
    Bytes 1-2: x (±1000) (10xmm)
    Bytes 3-4: y(±1000)
    Bytes 5-6: z (±1000)
    Bytes 7-8: rx (±180) (100xDeg)
    Bytes 9-10: ry (±180)
    Bytes 11-12: rz (±180)
    Feedback Data Bits: 0xFF 0x01

  4. Read World Coordinate System
    Function Code: 0x84
    Send Data Bits: None
    Feedback Data Bits:
    Bytes 1-2: x (±1000) (10xmm)
    Bytes 3-4: y (±1000)
    Bytes 5-6: z (±1000)
    Bytes 7-8: rx (±180) (100xDeg)
    Bytes 9-10: ry (±180)
    Bytes 11-12: rz (±180)

  5. Set Base Coordinate System
    Function Code: 0x85
    Send Data Bits: Byte 1: base type (0-base coordinate system 1-world coordinate system)
    Feedback Data Bits: 0xFF 0x01

  6. Read Base Coordinate System
    Function Code: 0x86
    Send Data Bits: None
    Feedback Data Bits: Byte 1: base type (0-Base Coordinate System 1-World Coordinate System)

  7. Set End Coordinate System
    Function Code: 0x89
    Send Data Bits: Byte 1: end type (0-Flange 1-Tool)
    Feedback Data Bits: 0xFF 0x01

  8. Read End Coordinate System
    Function Code: 0x8A
    Send Data Bits: None
    Feedback Data Bits: Byte 1: end type (0-Flange 1-Tool)

Error Clearing

  1. Clear Motion Errors
  2. Clear motion reading errors, such as exceeding limits, coordinates unreachable, etc.
    Function Code: 08
    Send Data Bits: None
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

  3. Joint Abnormal Recovery

  4. Clear some joint motor errors
    Function Code: 0xE7
    Send Data Bits: Byte 1: Joints 1-6, 254-All Joints
    Feedback Fixed Data Bits: Bytes 1-2: 0xFF 0x01

Introduction to 485 Modbus RTU Commands

Transmit/Receive Formats

Basic Parameters

Parameter Value (decimal) Value (hexadecimal)
Address 45 0x2D
Write Function Code 16 0x10
Read Function Code 03 0x03

Communication Frame Format

1. Write Command (Host → Device)
Field Length Hexadecimal Representation Description
Address 1 byte 0x2D Device Address: 45 (0x2D)
Function Code 1 byte 0x10 Write to multiple registers
Starting Register Address 2 bytes HH LL Register Start Address (low byte first)
Number of Registers 2 bytes HH LL Number of registers to write N
Number of Data Bytes 1 byte 0xMM Number of data bytes = 2×N
Data 2×N bytes DD DD ... Actual data (2 bytes per register)
Checksum 2 bytes CC CC Modbus CRC16 (low byte first)

Format: [Address-45][Function Code-0x10][Start Register Address-2 bytes][Number of Registers-2 bytes][Number of Data Bytes-1 byte][Data-2*N bytes][Checksum-2 bytes modbus_crc16-low byte first]

2. Write Feedback (Device → Host)
Fields Length Hexadecimal Representation Description
Address 1 byte 0x2D Device Address: 45 (0x2D)
Function Code 1 byte 0x10 Write Multiple Registers
Starting Register Address 2 bytes HH LL Register Start Address (Low Byte First)
Number of Registers 2 bytes HH LL Number of Registers Written
Checksum 2 bytes CC CC Modbus CRC16 (Low Byte First)

Format: [Address-45][Function Code-0x10][Starting Register Address-2 bytes][Number of Registers-2 bytes][Checksum-2 bytes modbus_crc16-Low Byte First]

3. Read Command (Host → Device)
Fields Length Hexadecimal Representation Description
Address 1 byte 0x2D Device Address: 45 (0x2D)
Function Code 1 byte 0x03 Read Multiple Registers
Starting Register Address 2 bytes HH LL Register Start Address (Low Byte First)
Number of Registers 2 bytes HH LL Number of Registers to Read N
Checksum 2 bytes CC CC Modbus CRC16 (Low Byte First)

Format: [Address-45][Function Code-03][Starting Register Address-2 bytes][Number of Registers-2 bytes][Checksum-2 bytes modbus_crc16-Low Byte First]

4. Read Feedback (Device → Host)
Field Length Hexadecimal Representation Description
Address 1 byte 0x2D Device Address: 45 (0x2D)
Function Code 1 byte 0x03 Read multiple registers
Number of Data Bytes 1 byte 0xMM Number of Data Bytes = 2×N
Data 2×N bytes DD DD ... Data read (2 bytes per register)
Checksum 2 bytes CC CC Modbus CRC16 (low byte first)

Format: [Address-45][Function Code-03][Number of Data Bytes-1 byte][Data-2*N bytes][Checksum-2 bytes modbus_crc16-low byte first]

Case Studies:
  1. Read angle in hexadecimal format: 2D 03 00 20 00 01 82 6C

Feedback: 2D 03 0C 23 28 00 10 11 94 00 20 03 A8 DC D8 3B 46

  1. Move all joints at 16% speed to [90, 0.16, 45, 0.32, 10, -90]: 2D 10 00 22 00 07 0E 23 28 00 10 11 94 00 20 03 A8 DC D8 00 10 66 60

First-level feedback: 2D 10 00 22 00 07 26 6D<br> Second layer feedback: Normal positioning:2D 10 00 5B 00 07 00 00 46 47, J1 over-limit:2D 10 00 5B 00 07 00 01 87 87`

Basic Control

  1. Read Main Control Version Number
    Register Address: 00 02
    Number of Registers: 00 01
    Feedback Data Bits: 2 bytes, requires /10.0
    Send Command (Hexadecimal): 2D 03 00 02 00 01 22 66
    Feedback Command Example: 2D 03 02 00 0A A9 85, version number is V1.0

  2. Start Robot
    Register Address: 00 16
    Number of Registers: 00 00
    Send Data Bits: None
    Feedback Data Bits: Bytes 1-2: Startup Status, 0-2; 0 - Startup Failed, 1 - Startup Successful, 2 - Emergency Stop Triggered

  3. Shut Down Robot
    Register Address: 00 17
    Number of Registers: 00 00
    Send data bits: None

  4. Read robot startup status
    Register address: 00 18
    Number of registers: 00 01
    Feedback data bits: Bytes 1-2: Startup status, 0-2; 0 - Startup failed, 1 - Startup successful, 2 - Emergency stop detected

Motion Control

  • Motion control speed range: 1-100, actual speed percentage can be found in the robotic arm motion and speed parameter table.
  • Position feedback format: [address][function code][register address][number of registers][position status][crc]
  • Position feedback data: Normal position: 2D 10 00 5B 00 07 00 00 46 47, J3 over-limit: 2D 10 00 5B 00 07 00 03 06 46

  • Full joint angle control
    Register address: 00 34
    Number of registers: 00 07
    Send data bits: Bytes 1-12: 2x6 joint angle (angle * 100.0) Bytes 13-14: Speed

  • Single joint angle control
    Register address: 00 33
    Number of registers: 00 03
    Transmit data bits: Bytes 1-2: Joint; Bytes 3-4: Angle (angle * 100.0); Bytes 5-6: Speed

  • Read all joint angles
    Register address: 00 32
    Number of registers: 00 01
    Feedback data bits: Bytes 1-12: 2x6 joint angle (angle / 100.0)

  • Full coordinate control
    Register address: 00 37
    Number of registers: 00 07
    Transmit data bits: Bytes 1-12: 2x6 coordinates (XYZ 10.0, RXRYRZ 100.0); Bytes 13-14: Speed

  • Single coordinate control
    Register address: 00 36
    Number of registers: 00 03
    Send data bits: Bytes 1-2: Coordinate axes; Bytes 3-4: Coordinates (XYZ10.0, RXRYRZ100.0); Bytes 5-6: Velocity

  • Read all coordinates
    Registry address: 00 35
    Number of registers: 00 01
    Feedback data bits: Bytes 1-12: 2x6 coordinates (XYZ/10.0, RXRYRZ/100.0)

  • Read robot motion status
    Registry address: 00 43
    Number of registers: 00 01
    Feedback data bits: Bytes 1-2: Motion status 0/1, 0 - not moving; 1 - moving

  • Pause motion
    Registry address: 00 38
    Number of registers: 00 01
    Send data bits: Bytes 1-2: 0/1 1 - Slow pause 0 - Emergency pause

  • Movement recovery
    Register address: 00 40
    Number of registers: 00 00
    Send data bits: None

  • Movement end
    Register address: 00 41
    Number of registers: 00 00
    Send data bits: None

  • Detect movement pause
    Register address: 00 39
    Number of registers: 00 01
    Feedback data bits: Bytes 1-2: Pause status 0/1, 0 - Not manually paused; 1 - Paused

  • Continuous joint movement
    Register address: 00 48
    Number of registers: 00 03
    Send data bits: Bytes 1-2: Joint; Bytes 3-4: Direction 0/1 0 - Reverse 1 - Forward Bytes 5-6: Speed

  • Continuous Coordinate Motion
    Registry Address: 00 50
    Number of Registers: 00 03
    Send Data Bits: Bytes 1-2: Coordinate Axis; Bytes 3-4: Direction 0/1 0 - Reverse 1 - Forward Bytes 5-6: Speed

  • RPY Rotation
    Registry Address: 00 245
    Number of Registers: 00 03
    Send Data Bits: Bytes 1-2: Mode 1-3 1 - Roll Angle 2 - Pitch Angle 3 - Yaw Angle; Bytes 3-4: Direction 0/1 0 - Reverse 1 - Forward Bytes 5-6: Speed

  • Joint Stepping Control
    Registry Address: 00 51
    Number of Registers: 00 03
    Send data bits: Bytes 1-2: Joint; Bytes 3-4: Step value * 100.0; Bytes 5-6: Speed

  • Coordinate Stepping Control
    Register Address: 00 52
    Number of Registers: 00 03
    Send data bits: Bytes 1-2: Coordinate axis; Bytes 3-4: Step value (XYZ 10.0, RXRYRZ 100.0); Bytes 5-6: Speed

  • Over-limit Return to Zero

  • After exceeding the limit, it is not necessary to manually move back to the limit; currently only supported in position mode, not in refresh mode control
    Register Address: 00 04
    Number of Registers: 00 00
    Send data bits: None

Auxiliary Functions

Configuration

  1. Set RGB Color
    Register Address: 00 12
    Number of Registers: 00 03
    Send Data Bits: Bytes 1-2: R; Bytes 3-4: G; Bytes 5-6: B Range 0-255, all 0s - light off

  2. Set Robot Torque Status
    Register Address: 00 19
    Number of Registers: 00 02
    Send Data Bits: Bytes 1-2: Joints 1-6 254 - All; Bytes 3-4: Mode 0/1 0 - Disabled 1 - Enabled; Movement is only possible when enabled

IO Control

Bottom IO
  1. Set Base IO Output
    Register Address: 00 160
    Number of Registers: 00 02
    Transmit data bits: Bytes 1-2: Pin numbers 1-12 Bytes 3-4: Status 0/1 0-Low level 1-High level

  2. Read dock I/O input
    Register address: 00 161
    Number of registers: 00 01
    Feedback data bits: Bytes 1-24: 2*12 pin status 0/1 0-Low level 1-High level

Terminal I/O
  1. Set terminal I/O output
    Register address: 00 97
    Number of registers: 00 02
    Transmit data bits: Bytes 1-2: Pin numbers 1/2 Bytes 3-4: Status 0/1 0-Low level 1-High level

  2. Read all terminal pin statuses
    Register address: 00 123
    Number of registers: 00 01
    Send data bits: None
    Feedback data bits: Bytes 1-2: Input 1 status 0/1 0-low level 1-high level; Bytes 3-4: Input 2 status; Bytes 5-6: End button 1 status; Bytes 7-8: End button 2 status

Status Query

  1. Read robot status
    Register address: 00 162
    Number of registers: 00 01
    Feedback data bits: Bytes 1-2: Collision detection status 0/1 1-collision; Bytes 3-4: Movement status 0/1 1-moving; Bytes 5-16: 1x6 joint over-limit status 0/1 1-over-limit; Bytes 17-28: 2x6 joint motor error status 0-normal >0 abnormal; Bytes 29-40: 2x6 joint motor software error 0-normal >0 abnormal; See error information and position feedback table for details

  2. Read Motion Error Information
    Registry Address: 00 07
    Number of Registers: 00 01
    Feedback Data Bits: Bytes 1-2: Error information, see error information and position feedback table for details

  3. Read Joint Running Speed
    Registry Address: 00 225
    Number of Registers: 00 01
    Feedback Data Bits: Bytes 1-12: 2x6 running speed / 100.0 +-30rpm

  4. Get Joint Current
    Registry Address: 00 226
    Number of Registers: 00 01
    Feedback Data Bits: Bytes 1-12: 2x6 joint current, unit: MA

Exception Clearing

  1. Clear Motion Errors
  2. Clear motion reading errors, such as exceeding limits, coordinates not reaching, etc.
    Registry Address: 00 08
    Number of registers: 00 00
    Data bits sent: None

  3. Joint Abnormal Recovery

  4. Clear some joint motor errors
    Register address: 00 231
    Number of registers: 00 01
    Data bits sent: Bytes 1-2: Joints 1-6, 254-All joints

Common Problems

  1. Robotic arm cannot move?
  2. Check if the robotic arm is enabled, if there are any errors in the joint motors, and if any joints are out of limits. You can call Read Robot Status.
  3. No response to commands
  4. Check if the sent commands are correct. All commands have a first-level handshake feedback.

Error Messages and Position Feedback Form

Position Feedback Form

0-20 Joint Overlimit, Collision, Pause, etc.

Hexadecimal (Decimal) Description
0 Movement in Position
1-7 Joint Overlimit
8 End of Movement Mode Setting
10-13 Collision Protection
A (10) End of Ease Marker
B (11) Command Stop Marker

20-23 (32-35) Coordinate motion anomaly (Check joint limits)

Hexadecimal (Decimal) Description
20 (32) No coordinate solution
21 (33) No adjacent solution for linear motion
22 (34) Velocity fusion error
23 (35) No adjacent solution for zero-space motion
24 (36) No solution for singular position
31 (49) Identification accuracy error

41-47 (65-71) Joint Abnormality

Hexadecimal (Decimal) Description
41-47 (65-71) 1-7 Joint Position Accuracy Abnormality
51-57 (81-87) 1-7 Joint Collision Detection Abnormality
0x61-67 1-7 Joint CAN Transmission Failure
0x71-77 1-7 Joint CAN Reception Abnormality
0x81-87 1-7 Joint Enabled
0x91-97 1-7 Joint Motor Error (Can be used with 0x9c interface after error)
0xA1-A7 1-7 Joint Motor Encoder Error
0xC1-C7 1-7 Joint Position Out of Tolerance


Motion Error Message Table

Return Data Format: 0xD0 + xx (e.g., 0xD001 indicates 1 joint exceeds limit)

0-6 Joint Exceeds Limit

Status Code (Decimal) Hexadecimal Description
0 0x00 Normal Motion
1 0x01 1 Joint Exceeds Limit
2 0x02 2 Joints Exceeds Limit
3 0x03 3 Joints Exceeds Limit
4 0x04 4 Joints Exceeds Limit
5 0x05 5 Joints Exceeds Limit
6 0x06 6 Joints Exceeds Limit

20-24 (32-36) Coordinate Motion Abnormality

Status Code (Decimal) Hexadecimal Explanation
20 (32) 0x14 No solution for coordinates, please check if the arm span is near the limit
21 (33) 0x15 No adjacent solution for linear motion
22 (34) 0x16 Velocity fusion error
23 (35) 0x17 No adjacent solution for zero-space motion
24 (36) 0x18 No solution for singular position, please use joint control to leave the singular point


Joint Motor Error Message Table

1. Software Error Alarms

Bits (2 bytes) Error Status (1 - Abnormal, 0 - Normal) Description and Handling Suggestions
0 Can Initialization Abnormal Requires checking the main control board. After fixing the control board abnormality, power off and then power on again.
Symptoms: The machine cannot be enabled or controlled, etc.
1 Motor Initialization Abnormal Requires checking the motor communication line, etc. After fixing the abnormality, power off and then power on again.
Symptoms: The machine cannot properly feedback joint information or control, etc.
2 Motor Sending Abnormal Requires checking the motor communication line, etc.
Symptoms: Abnormal machine position feedback, etc.; can be cleared using abnormal recovery.
3 Motor Receiving Abnormal Requires checking the motor communication line, etc.
Symptoms: Abnormal machine position feedback, etc.; can be cleared using abnormal recovery.
This feedback allows normal machine control and does not require user notification; it is mainly used for troubleshooting.
4 Position Out of Tolerance Requires checking the motor encoder, etc.
Symptoms: Machine is disabled and cannot be controlled; can be cleared using exception recovery.
5 End-point transmission anomaly Need to check end-point communication lines, etc.Symptoms: End-point interface feedback anomaly; can be cleared using exception recovery.
6 End-point reception anomaly Need to check end-point communication lines, etc.Symptoms: End-point interface feedback anomaly; can be cleared using exception recovery.This feedback allows normal machine control without user notification; mainly used for troubleshooting anomalies.
7 Motor encoder error When the encoder reports an error, movement is impossible; the encoder error needs to be cleared.Older motor drive boards do not report errors - even if an encoder error is reported, the software cannot provide feedback.How to distinguish between new and old: The board with a battery is the newer drive board.
8 Disabled feedback The machine must be enabled before movement.

2 Motor Built-in Error Alarms

Bits (2 bytes) Error Status Handling Method
0 CAN Bus Error Can be recovered using exception recovery. If recovery fails, check the communication line, repair, and then power on to enable.
1 Short Circuit Can be recovered using exception recovery.
2 Invalid Setting Data
3 Control Error Can be recovered using exception recovery.
4 CAN Communication Error Can be recovered using exception recovery. If recovery fails, check the communication line, repair, and then power on to enable.
5 Feedback Error Can be recovered using exception recovery.
6 Positive Limit Switch Activated
7 Negative Limit Switch Activated
8 Overcurrent Can be recovered using exception recovery.
9 I2t Protection Can be recovered using exception recovery.
10 Overtemperature Can be recovered using exception recovery.
11 Driver Board Overtemperature Can be recovered using exception recovery.
12 Overvoltage Can be recovered using exception recovery.
13 Undervoltage Can be recovered using exception recovery.
14 Command Error
15 Enabled is inactive


← Previous Chapter | Next Chapter →

results matching ""

    No results matching ""