Skip to content

End-Effector Tool gripper configuration gripperControl

The end effector of RealMan robotic arms 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 effector modbus functionality). This interface is used to control the stroke, opening and closing, grasping position, and grasping force, and to read the state of the EG2-4C2 gripper.

Set gripper strokerm_set_gripper_route()

Set gripper stroke, which 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:
C
int rm_set_gripper_route(rm_robot_handle * handle,int min_limit,int max_limit)

Jump to rm_robot_handle for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
min_limitInputMinimum opening value of the gripper, range: 0-1,000, without unit of measurement.
max_limitInputMaximum opening value of the gripper, range: 0-1,000, without unit of measurement.
  • Return value:
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.
  • Usage demo
C
//Set the minimum opening value of the gripper to 70 and the maximum value to 500
int min_limit = 70;
int max_limit = 500;
ret=rm_set_gripper_route(robot_handle,min_limit,max_limit);

Release gripperrm_set_gripper_release()

Release the gripper, which means that the gripper moves to the maximum opening position at the specified speed.

  • Method prototype:
C
int rm_set_gripper_release(rm_robot_handle * handle,int speed,bool block,int timeout)

Jump to rm_robot_handle for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
speedInputRelease speed of the gripper, range: 1-1,000, without unit of measurement.
blockInputtrue indicates blocking mode, where the system waits for the controller to return the gripper's in-position command; false indicates non-blocking mode, where no in-position command is received.
timeoutInputBlocking 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:
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
C
//The gripper releases at a speed of 500. If no response is received within 10 seconds, a timeout triggers.
int speed =500;
ret = rm_set_gripper_release(robot_handle, speed, true, 10);

Gripper force-controlled graspingrm_set_gripper_pick()

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

  • Method prototype:
C
int rm_set_gripper_pick(rm_robot_handle * handle,int speed,int force,bool block,int timeout)

Jump to rm_robot_handle for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
speedInputRelease speed of the gripper, range: 1-1,000, without unit of measurement.
forceInputForce control threshold, range: 50-1,000, without unit of measurement.
blockInputtrue indicates blocking mode, where the system waits for the controller to return the gripper's in-position command; false indicates non-blocking mode, where no in-position command is received.
timeoutInputBlocking 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:
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
C
//Set the grasping speed to 500, and the torque threshold to 200. If no response is received within 10 seconds, a timeout triggers
int speed = 500;
int force = 200;
ret = rm_set_gripper_pick(robot_handle,speed,force,true,10);

Gripper continuous force-controlled graspingrm_set_gripper_pick_on()

  • Method prototype:
C
int rm_set_gripper_pick_on(rm_robot_handle * handle,int speed,int force,bool block,int timeout)

Jump to rm_robot_handle for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
speedInputRelease speed of the gripper, range: 1-1,000, without unit of measurement.
forceInputForce control threshold, range: 50-1,000, without unit of measurement.
blockInputtrue indicates blocking mode, where the system waits for the controller to return the gripper's in-position command; false indicates non-blocking mode, where no in-position command is received.
timeoutInputBlocking 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:
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
C
//Set the grasping speed to 500, and the grasping torque threshold to 200. If no response is received within 10 seconds, a timeout triggers.
int speed = 500;
int force = 200;
ret =  rm_set_gripper_pick_on(robot_handle,speed,force,true,10);

Set gripper to a specified positionrm_set_gripper_position()

Gripper reaches specified position: When the current opening is smaller than the specified opening, the gripper releases at the specified speed to reach the desired position. When the current opening is larger than the specified opening, the gripper closes at the specified speed and torque to reach the target position. The gripper stops when the gripping force exceeds the torque threshold or when the specified position is reached.

  • Method prototype:
C
int rm_set_gripper_position(rm_robot_handle * handle,int position,bool block,int timeout)

Jump to rm_robot_handle for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
positionInputOpening position of the gripper, range: 1-1,000, without unit of measurement.
blockInputtrue indicates blocking mode, where the system waits for the controller to return the gripper's in-position command; false indicates non-blocking mode, where no in-position command is received.
timeoutInputBlocking 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:
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
C
//Control the gripper to reach an opening of 500. If no response is received within 10 seconds, a timeout triggers.
int position = 500;
ret = rm_set_gripper_position(robot_handle,position,true,10);

##Query gripper staterm_get_gripper_state()

  • Method prototype:
C
int rm_get_gripper_state(rm_robot_handle * handle,rm_gripper_state_t * state)

Jump to rm_robot_handle and rm_gripper_state_t for details of the structure

  • Parameter description:
ParameterTypeDescription
handleInputRobotic arm handle.
stateOutputStore the gripper status structure.
  • Return value:
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.

Note: By default, this interface does not update data. State updates are enabled starting from the first control of the gripper. However, if the dexterous hand is controlled or the end effector modbus functionality is activated, data updates will be disabled. Additionally, the gripper must support the latest firmware to enable this feature.

  • Usage demo
C
//Get gripper state
rm_gripper_state_t state;
ret = rm_get_gripper_state(handle, &state);