Skip to content

Gripper Configuration gripperControl

It is used to control the gripper and get its state. The RealMan robotic arm supports various common grippers. In the system, the INSPIRE-ROBOTS EG2-4C2 gripper is adapted for use. To facilitate user operation of the gripper, the robotic arm controller provides an open gripper control protocol (the gripper control protocol is mutually exclusive with the end modbus functionality). The following is a detailed description of the member functions of the gripper configuration gripperControl, including the method prototype, parameter description, return value, and usage demo.

Set gripper strokerm_set_gripper_route()

It refers to the maximum and minimum opening values of the gripper. Once set successfully, the values are saved automatically and will not be lost when the gripper is powered off.

  • Method prototype:
python
rm_set_gripper_route(self, min_route: int, max_route: int) -> int:
  • Parameter description:
ParameterTypeDescription
min_routeintMinimum opening value of the gripper, range: 0−1,000, without a unit of measurement; max_route (int): maximum opening value of the gripper, range: 0−1,000, without a unit of measurement
  • Return value: State codes executed by functions:
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
-4intTimeout.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_set_gripper_route(70, 200))

arm.rm_delete_robot_arm()

Release gripperrm_set_gripper_release()

The gripper moves to the maximum opening position at the specified speed.

  • Method prototype:
python
rm_set_gripper_release(self, speed: int, block: bool, timeout: int) -> int:
  • Parameter description:
ParameterTypeDescription
speedintRelease speed of the gripper, range: 1−1,000, without a unit of measurement.
blockbooltrue: blocking mode, where the system waits for the controller to return the gripper in-position command; false: non-blocking mode, where no gripper in-position command is received.
timeoutintBlocking mode: set the timeout period for waiting for the in-position gripper, in s; non-blocking mode: 0: immediately return after sending the command; other values: return after receiving the successful setting command.
  • Return value: State codes executed by functions
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
-4intTimeout.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_set_gripper_release(500, True, 10))

arm.rm_delete_robot_arm()

Gripper force-controlled graspingrm_set_gripper_pick()

The gripper grasps with the set speed and force. When the gripping force exceeds the preset threshold, the grasping operation stops.

  • Method prototype:
python
rm_set_gripper_pick(self, speed: int, force: int, block: bool, timeout: int) -> int:
  • Parameter description:
ParameterTypeDescription
speedintGrasping speed of the gripper, range: 1−1,000, without a unit of measurement
forceintForce control threshold, range: 50−1,000, without a unit of measurement
blockbooltrue: blocking mode, where the system waits for the controller to return the gripper in-position command; false: non-blocking mode, where no gripper in-position command is received.
timeoutintBlocking mode: set the timeout period for waiting for the in-position gripper, in s; non-blocking mode: 0: immediately return after sending the command; other values: return after receiving the successful setting command.
  • Return value: State codes executed by functions:
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
-4intTimeout.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_set_gripper_pick(500, 200, True, 10))

arm.rm_delete_robot_arm()

Gripper continuous force-controlled graspingrm_set_gripper_pick_on()

  • Method prototype:
python
rm_set_gripper_pick_on(self, speed: int, force: int, block: bool, timeout: int) -> int:
  • Parameter description:
ParameterTypeDescription
speedintGrasping speed of the gripper, range: 1−1,000, without a unit of measurement.
forceintForce control threshold, range: 50−1,000, without a unit of measurement.
blockbooltrue: blocking mode, where the system waits for the controller to return the gripper in-position command; false: non-blocking mode, where no gripper in-position command is received.
timeoutintBlocking mode: set the timeout period for waiting for the in-position gripper, in s; non-blocking mode: 0: immediately return after sending the command; other values: return after receiving the successful setting command.
  • Return value: State codes executed by functions:
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
-4intTimeout.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_set_gripper_pick_on(500, 200, True, 10))

arm.rm_delete_robot_arm()

Set gripper to a specified positionrm_set_gripper_position()

  • Method prototype:
python
rm_set_gripper_position(self, position: int, block: bool, timeout: int) -> int:
  • Parameter description:
ParameterTypeDescription
positionintOpening position of the gripper, range: 1−1,000, without a unit of measurement
blockbooltrue: blocking mode, where the system waits for the controller to return the gripper in-position command; false: non-blocking mode, where no gripper in-position command is received.
timeoutintBlocking mode: set the timeout period for waiting for the in-position gripper, in s; non-blocking mode: 0: immediately return after sending the command; other values: return after receiving the successful setting command.
  • Return value: State codes executed by functions:
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
-4intTimeout.
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_set_gripper_position(500, True, 10))

arm.rm_delete_robot_arm()

Query gripper staterm_get_gripper_state()

  • Method prototype:
python
rm_get_gripper_state(self) -> tuple[int, dict[str, any]]:
  • Return value:tuple[int,dict[str, any]]: a tuple containing two elements.
  1. int: state codes executed by functions.
ParameterTypeDescription
0intSuccess.
1intThe controller returns false, indicating that the parameters are sent incorrectly or the robotic arm state is wrong.
-1intThe data transmission fails, indicating that a problem occurs during the communication.
-2intThe data reception fails, indicating that a problem occurs during the communication, or the controller has a return timeout.
-3intThe return value parse fails, indicating that the received data format is incorrect or incomplete.
  1. Gripper state information
ParameterTypeDescription
rm_gripper_state_tdict[str, any]Dictionary of gripper state information, key: field name of rm_gripper_state_t
  • Usage demo
python
from Robotic_Arm.rm_robot_interface import *

# Instantiate the RoboticArm class
arm = RoboticArm(rm_thread_mode_e.RM_TRIPLE_MODE_E)

# Create the robotic arm connection and print the connection ID
handle = arm.rm_create_robot_arm("192.168.1.18", 8080)
print(handle.id)

print(arm.rm_get_gripper_state())

arm.rm_delete_robot_arm()