Skip to content

3.Control

3.1.Use xArm Studio to Control xArm Gripper

  1. Set up xArm Gripper
  • Control the xArm gripper in the live control

Control Method:

  1. By dragging this progress bar, you can control the opening and closing stroke of the gripper.

img_6.png

  • Control the xArm gripper through Blockly

Find the example file 1007_xArm_Gripper in the blockly module

img_8.png

The role of this program: execute this program to control the gripper to pick the target object at the specified position, and then place the target object at the target position.

Note:

  1. When the gripper is installed on the robotic arm, the TCP Payload of the gripper should be set in the Blockly program. When the total weight of the gripper changes after the object is picked, a new TCP Payload needs to be set.

3.2.Use Python-SDK to Control xArm Gripper

For details on controlling Gripper with python-SDK, please refer to the link below:

https://github.com/xArm-Developer/xArm-Python-SDK/blob/master/example/wrapper/common/5004-set_gripper.py

3.3.Use ROS-SDK to Control xArm Gripper

Please refer to Section 5.7.7 in the ReadMe file attached to the ROS package to control the gripper. xArm ROS-SDK link :

https://github.com/xArm-Developer/xarm_ros

3.4.Use Private Protocol Communication Protocol to Control xArm Gripper

This section mainly explains how to control the xArm Gripper by using the Private Protocol protocol through xArm control box.

3.4.1.Private Protocol Communication Format

Private Protocol:

Modbus protocol is an application layer message transmission protocol, including three message types: ASCII, RTU, and TCP. The standard Modbus protocol physical layer interface includes RS232, RS422, RS485 and Ethernet interfaces, and adopts master / slave communication. Private Protocol Communication Process:

1.Establish a TCP connection

2.Prepare Modbus messages

3.Use the send command to send a message

4.Waiting for a response under the same connection

5.Use the recv command to read the message and complete a data exchange

6.When the communication task ends, close the TCP connection

Parameter:

Default TCP Port: 502 Protocol: 0x00 0x02

On the problem of users using communication protocols to organize data in big endian and little endian:

In this article, data analysis is big-endian analysis.

3.4.2.Read xArm Gripper Register

3.4.2.1. Register Function

Read Register
Request
MBTP HeaderTransaction Identifier2 Bytes0x0001
Protocol Identifier2 Bytes0x0002
Length2 Bytes6+N*x2
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x03
Register Starting Address2 BytesAddress
Quantity of RegistersN*x2 BytesN*
Response
MBTP HeaderTransaction Identifier2 Bytes0x0001
Protocol Identifier2 Bytes0x0002
Length2 Bytes6+N*x2
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x03
Byte Count1 ByteN*x2
Registers ValueN*x2 BytesValue

N* = Quantity of Registers Address = Register Starting Address

Resgister:

Resgister Starting AddressRegisters Value
Get Gripper status Register0x00002 BytesStop status: : 0x0000 Motion status: 0x0001Clipping status: 0x0010
Get Gripper position Register0x07024bytes0xFFFFFFFB-0x00000320
Get Gripper Error Register0x000F2 BytesAn error occurs: all other return values indicate an error(except 0)No error occurred: 0x0000

3.4.2.2.Example

1.Get the xArm Gripper status

Get the xArm Gripper status
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x08
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x03
Register Starting Address2 Bytes0x00,0x00
Quantity of Registers2 Bytes0x00,0x01
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x08
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x03
Byte Count1 Byte0x02
Registers Value(Robotic arm is in motion status)2 Bytes0x00,0x01

2.Get the xArm Gripper position

Get the xArm Gripper position
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x08
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x03
Register Starting Address2 Bytes0x07,0x02
Quantity of Registers2 Bytes0x00,0x02
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x03
Byte Count1 Byte0x04
Registers Value(position: 400)4 Bytes0x00,0x00,0x01,0x90

3.Get the xArm Gripper Error

Get the xArm Gripper Error
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x08
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x03
Register Starting Address2 Bytes0x00,0x0F
Quantity of Registers2 Bytes0x00,0x01
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x08
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x03
Byte Count1 Byte0x02
Registers Value(No error occurred in the Gripper)2 Bytes0x00,0x00

3.4.3.Write xArm Gripper Register

3.4.3.1. Register Function

Write Register
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes9+N*x2
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 BytesAddress
Quantity of Registers2 BytesN*
Byte Count1 ByteN*x2
Registers ValueN*x2 BytesValue
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 BytesAddress
Quantity of Registers2 BytesN*

N* = Quantity of Registers

Address = Register Starting Address

Resgister:

Resgister Starting AddressRegisters Value
Set Gripper Mode Register0x01012bytesPosition mode: 0x0000
Enable/Disable Gripper Register0x01002 BytesEnable : 0x0001 Disable : 0x0000
Set Gripper Position Register0x07004 BytesOpen the Gripper : 0x0000 0x0082 Close the Gripper : 0x0000 0x0032
Set Position Speed Register0x03032 Bytes0x0100-0x0400 Unit : r/min

3.4.3.2.Example

1.Set xArm Gripper Mode

Set xArm Gripper Mode
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x0B
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x01
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value(Position mode)2 Bytes0x00,0x00
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x01
Quantity of Registers2 Bytes0x00,0x01

2.Enable/Disable xArm Gripper

Enable/Disable xArm Gripper
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x0B
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x00
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value2 Bytes0x00,0x01
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x00
Quantity of Registers2 Bytes0x00,0x01

3.Set xArm Gripper Speed

Set xArm Gripper Speed
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x0B
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x03,0x03
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value(1500r/min)2 Bytes0x05,0xDC
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x03,0x03
Quantity of Registers2 Bytes0x00,0x01

4.Set xArm Gripper Position

Set xArm Gripper Position
Request
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x0D
Unit Identifier1 Byte0x7C
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x07,0x00
Quantity of Registers2 Bytes0x00,0x02
Byte Count1 Byte0x04
Registers Value(400)4 Bytes0x00,0x00,0x01,0x90
Response
MBTP HeaderTransaction Identifier2 Bytes0x00,0x01
Protocol Identifier2 Bytes0x00,0x02
Length2 Bytes0x00,0x09
Unit Identifier1 Byte0x7C
Status Value1 Byte0x00
ParametersSate1 Byte0x00
Internal UseInternal Use1 Byte0x09
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x07,0x00
Quantity of Registers2 Bytes0x00,0x02

3.4.4.xArm Gripper Control Process

The complete process of controlling the motion of the xArm Gripper is as follows:

(1) Enable the Gripper

0x00, 0x01, 0x00, 0x02, 0x00, 0x0B, 0x7C, 0x09, 0x08, 0x10, 0x01, 0x00, 0x00, 0x01, 0x02, 0x00, 0x01

(2) Open the Gripper

0x00, 0x01, 0x00, 0x02, 0x00, 0x0D, 0x7C, 0x09, 0x08, 0x10, 0x07, 0x00, 0x00, 0x02, 0x04, 0x00, 0x00, 0x01, 0x90

(3) Close the Gripper

0x00, 0x01, 0x00, 0x02, 0x00, 0x0D, 0x7C, 0x09, 0x08, 0x10, 0x07, 0x00, 0x00, 0x02, 0x04, 0x00, 0x00, 0x00, 0x32

3.5.Use Modbus-RTU Communication Protocol to Control xArm Gripper

3.5.1.Modbus RTU Communication Format

img_14.png

The gripper defaults to the standard Modbus RTU protocol at a default baud rate is 2Mbps and the slave ID is 0x08. The currently supported function codes are: 0x03 / 0x10. In this article, data analysis is big-endian analysis.

Read Register
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x03
Register Starting Address2 BytesAddress
Quantity of Register2 BytesN*
Modbus CRC162 BytesCRC*
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x03
Byte Count1 ByteN*x2
Registers ValueN*x2 BytesValue
Modbus CRC162 BytesCRC*

3.5.2.Read xArm Gripper Register

N* = Quantity of Registers

Address = Register Starting Address

CRC* = Cyclic Redundancy Check

Resgister:

Resgister Starting AddressRegister Value
Get Gripper status Register0x00002 BytesStop status: : 0x0000 Motion status: 0x0001Clipping status: 0x0010
Get Gripper position Register0x07024bytes0xFFFFFFFB-0x00000320
Get Gripper Error Register0x000F2 BytesAn error occurs: all other return values indicate an error(except 0)No error occurred: 0x0000

3.5.3.Write xArm Gripper Register

Write Register
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 BytesAddress
Quantity of Register2 BytesN*
Byte Count1 ByteN*x2
Registers ValueN*x2 BytesValue
Modbus CRC162 BytesCRC*
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 BytesAddress
Quantity of Registers2 BytesN*
Modbus CRC162 BytesCRC*

N* = Quantity of Registers

Address = Register Starting Address

CRC* = Cyclic Redundancy Check

Resgister:

Resgister Starting AddressRegister Value
Enable/Disable Gripper Register0x01002 BytesEnable : 0x0001 Disable : 0x0000
Set Gripper Position Register0x07004 BytesOpen the Gripper: 0x0000 0x0082 Close the Gripper: 0x0000 0x0032
Set Position Speed Register0x03032 Bytes0x0100-0x0400 Unit: r/min
Set Gripper Mode Register0x01012bytesPosition mode: 0x0000

3.5.4.Modbus RTU Example

This section demonstrates the example given in the Control Logic section when programmed using the Modbus RTU protocol.

Step1:Set xArm Gripper Mode

Set xArm Gripper Mode
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x01
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value2 Bytes0x00,0x00
Modbus CRC162 Bytes0xDD,0x11
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x01
Quantity of Registers2 Bytes0x00,0x01
Modbus CRC162 Bytes0x51,0x6C

Step2:Enable xArm Gripper

Enable xArm Gripper
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x00
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value2 Bytes0x00,0x01
Modbus CRC162 Bytes0x1D,0x00
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x01,0x00
Quantity of Registers2 Bytes0x00,0x01
Modbus CRC162 Bytes0x00,0xAC

Step3:Set xArm Gripper Speed

Set xArm Gripper Speed
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x03,0x03
Quantity of Registers2 Bytes0x00,0x01
Byte Count1 Byte0x02
Registers Value(1500r/min)2 Bytes0x05,0xDC
Modbus CRC162 Bytes0xFD,0xFA
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x03,0x03
Quantity of Registers2 Bytes0x00,0x01
Modbus CRC162 Bytes0xF1,0x14

Step4:Set xArm Gripper Position

Set xArm Gripper Position
Request
Modbus RTU DataSlave ID (Gripper)1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x07,0x00
Quantity of Registers2 Bytes0x00,0x02
Byte Count1 Byte0x04
Registers Value(position:400)4 Bytes0x00,0x00,0x01,0x90
Modbus CRC162 Bytes0xFA,0xFF
Response
Modbus RTU DataSlave ID1 Byte0x08
Function Code1 Byte0x10
Register Starting Address2 Bytes0x07,0x00
Quantity of Registers2 Bytes0x00,0x02
Modbus CRC162 Bytes0x40,0x25