Skip to content

Modbus Slave Address Table of the RM Robotic Arm

The RealMan robotic arm supports the Modbus slave, which is available on both Modbus-RTU and Modbus-TCP, and all the slaves share the address table and functions.

  • Modbus-TCP: Use the Ethernet port or WiFi for communication, with parameters set as follows: IP address: IP address of the robotic arm; port number: 502; and device ID: 1.
  • Modbus-RTU: Use the controller 485 port for communication, with parameters set as follows: baud rate: 9600, 115200, or 460800; and slave address: 01.

Note: When users customize the register addresses, it is preferred to use the 3000 or later to prevent conflicts between the address occupation caused by program upgrades and the user-defined function.

1. Address description

1.1 Coil

AddressFunctionValue Description
0Digital IO1 mode0: input;
1: output
1Digital IO10: low;
1: high
2Digital IO2 mode0: input;
1: output
3Digital IO20: low;
1: high
4Digital IO3 mode0: input;
1: output
5Digital IO30: low;
1: high
6Digital IO4 mode0: input;
1: output
7Digital IO40: low;
1: high
48Joint1 enabling state0: disable;
1: enable (control temporarily unavailable)
49Joint2 enabling state0: disable;
1: enable (control temporarily unavailable)
50Joint3 enabling state0: disable;
1: enable (control temporarily unavailable)
51Joint4 enabling state0: disable;
1: enable (control temporarily unavailable)
52Joint5 enabling state0: disable;
1: enable (control temporarily unavailable)
53Joint6 enabling state0: disable;
1: enable (control temporarily unavailable)
54Joint7 enabling state0: disable;
1: enable (control temporarily unavailable)

1.2 Discrete input

AddressFunctionValue Description
0Digital IO1 mode0: input;
1: output
1Digital IO10: low;
1: high
2Digital IO2 mode0: input;
1: output
3Digital IO20: low;
1: high
4Digital IO3 mode0: input;
1: output
5Digital IO30: low;
1: high
6Digital IO4 mode0: input;
1: output
7Digital IO40: low;
1: high

1.3 Holding register

For the address ranges from 2000 to 2200 (including), the automatic saving is realized after the register powers off.

AddressFunctionValue Description
0VOUT Output voltage0: 0 V;
2: 12 V;
3: 24 V
1Number of the given program, range: 1−100. The data is cleared after the controller runs the program, and it is set to -1 if the run fails.Input: 1−100
Output: 0: success; -1: failure
2Given running speed, range: 1−100. After register 1 starts the robotic arm program, the speed takes effect, and the data is clearedSpeed range: 1−100
3Control program, range: 1−3. The data is cleared after being detected by the controller.1: emergency stop;
2: pause;
3: continuation
1−149Reserved
150Two high bytes of motion position parameter 1
151Two low bytes of motion position parameter 1
152Two high bytes of motion position parameter 2
153Two low bytes of motion position parameter 2
154Two high bytes of motion position parameter 3
155Two low bytes of motion position parameter 3
156Two high bytes of motion position parameter 4
157Two low bytes of motion position parameter 4
158Two high bytes of motion position parameter 5
159Two low bytes of motion position parameter 5
160Two high bytes of motion position parameter 6
161Two low bytes of motion position parameter 6
162Two high bytes of motion position parameter 7
163Two low bytes of motion position parameter 7
164Two high bytes of motion position parameter 8
165Two low bytes of motion position parameter 8
166Two high bytes of motion position parameter 9
167Two low bytes of motion position parameter 9
168Two high bytes of motion position parameter 10
169Two low bytes of motion position parameter 10
170Two high bytes of motion position parameter 11
171Two low bytes of motion position parameter 11
172Two high bytes of motion position parameter 12
173Two low bytes of motion position parameter 12
174−179Reserved
180Motion type1: MoveJ;
2: MoveJ_P;
3: MoveL;
4: MoveC
181Motion command: 1: start; 2: stop
182Speed percentage1−100
183Two high bytes of the blend radius
184Two low bytes of the blend radius
185Loop count
228Get and set the current collision stage. This address can be used to get and set the current collision stage. Only the stages consistent with those in the JSON protocol are supported. If the value is beyond the range, the maximum stage 8 is automatically appliedCollision stage: 0−8
229Real-time speed adjustment of motion1-100 speed ratio

1.4 Input register

AddressFunctionValue Description
0End effector position X, in mmUnsigned integer and two's complement for negative numbers
1End effector position Y, in mmUnsigned integer and two's complement for negative numbers
2End effector position Z, in mmUnsigned integer and two's complement for negative numbers
3End effector orientation RX, in radUnsigned integer and two's complement for negative numbers
4End effector orientation RY, in radUnsigned integer and two's complement for negative numbers
5End effector orientation RZ, in radUnsigned integer and two's complement for negative numbers
6Joint1 angle, in °Unsigned integer and two's complement for negative numbers
7Joint2 angle, in °Unsigned integer and two's complement for negative numbers
8Joint3 angle, in °Unsigned integer and two's complement for negative numbers
9Joint4 angle, in °Unsigned integer and two's complement for negative numbers
10Joint5 angle, in °Unsigned integer and two's complement for negative numbers
11Joint6 angle, in °Unsigned integer and two's complement for negative numbers
12Joint7 angle, in °Unsigned integer and two's complement for negative numbers
13Joint1 current, in mAUnsigned integer and two's complement for negative numbers
14Joint2 current, in mAUnsigned integer and two's complement for negative numbers
15Joint3 current, in mAUnsigned integer and two's complement for negative numbers
16Joint4 current, in mAUnsigned integer and two's complement for negative numbers
17Joint5 current, in mAUnsigned integer and two's complement for negative numbers
18Joint6 current, in mAUnsigned integer and two's complement for negative numbers
19Joint7 current, in mAUnsigned integer and two's complement for negative numbers
20Joint1 voltage, in VUnsigned integer and two's complement for negative numbers
21Joint2 voltage, in VUnsigned integer and two's complement for negative numbers
22Joint3 voltage, in VUnsigned integer and two's complement for negative numbers
23Joint4 voltage, in VUnsigned integer and two's complement for negative numbers
24Joint5 voltage, in VUnsigned integer and two's complement for negative numbers
25Joint6 voltage, in VUnsigned integer and two's complement for negative numbers
26Joint7 voltage, in VUnsigned integer and two's complement for negative numbers
27Joint1 temperature, in °CUnsigned integer and two's complement for negative numbers
28Joint2 temperature, in °CUnsigned integer and two's complement for negative numbers
29Joint3 temperature, in °CUnsigned integer and two's complement for negative numbers
30Joint4 temperature, in °CUnsigned integer and two's complement for negative numbers
31Joint5 temperature, in °CUnsigned integer and two's complement for negative numbers
32Joint6 temperature, in °CUnsigned integer and two's complement for negative numbers
33Joint7 temperature, in °CUnsigned integer and two's complement for negative numbers
34System error code, refer to the JSON protocol for details
35Heart rate (+1 per second)
36Position X, in mmFloat
38Position Y, in mmFloat
40Position Z, in mmFloat
42Orientation RX, in radFloat
44Orientation RY, in radFloat
46Orientation RZ, in radFloat
48Joint1 angle, in °Float
50Joint2 angle, in °Float
52Joint3 angle, in °Float
54Joint4 angle, in °Float
56Joint5 angle, in °Float
58Joint6 angle, in °Float
60Joint7 angle, in °Float
99Program running state0: not started;
1: running;
3: paused
100Number of program lines of the robotic arm
101ID of the currently running program, 0: no trajectory saved
200Joint1 error codeRefer to the JSON protocol for details
201Joint2 error codeRefer to the JSON protocol for details
202Joint3 error codeRefer to the JSON protocol for details
203Joint4 error codeRefer to the JSON protocol for details
204Joint5 error codeRefer to the JSON protocol for details
205Joint6 error codeRefer to the JSON protocol for details
206Joint7 error codeRefer to the JSON protocol for details
300Motion in position along planned trajectory0: motion not in position; 1: motion in position; 2: planning failed
301Trajectory planning state0: no planning; 1: planning
302Emergency Stop Status0 indicates entering emergency stop

2. Data conversion

The following is a conversion from the register value to the angle in float type:

C
    float fun(quint16 H,quint16 L)
    {
        FloatTo4Bytes uValue;
        uValue.Byte[3] = (H >> 8) & 0xFF;
        uValue.Byte[2] = H & 0x00FF;
        uValue.Byte[1] = (L >> 8) & 0xFF;
        uValue.Byte[0] = L & 0x00FF;
        return uValue.a;
    }

3. Demo of motion control

For MoveJ, the demo of holding register addresses and target joint angles is as follows:

Address150151152153154155156157158159160161
H(0x)437452f241c64bc744430d503dae147bbf72f1aa404072b0
Data-11.252-0.921-28.067417.812-26.277-13.981

Description: Register addresses 150−161 store the target angles of joints 1−6, and two adjacent register addresses store a joint angle, in float type and with high bits in front. Conversion from the angle in float type to the register value:

C
void fun(float value, quint16 *H, quint16 *L)
{
    quint8 buf[4] = {0};
    memcpy(buf, &value, sizeof(float));
    *H = ((quint16)buf[3]<<8)|buf[2];
    *L = ((quint16)buf[1]<<8)|buf[0];
}

Demo of MoveJ holding register addresses and motion control parameters:

Address180181182183184185
D1150001
TypeMotion typeMotion commandSpeedBlend radiusBlend radiusLoop

Description:

  1. Address 180: current motion type, 0: None; 1: MoveJ; 2: MoveJ_P; 3: MoveL; 4: MoveC;
  2. Address 181: motion command, 1: start; 2: stop;
  3. Address 182: speed percentage, 0−100;
  4. Address 183: high bits of blend radius;
  5. Address 184: low bits of blend radius;
  6. Address 185: Loop count (for MoveC only).