pymoveit2.gripper_command module

class pymoveit2.gripper_command.GripperCommand(node: rclpy.node.Node, gripper_joint_names: List[str], open_gripper_joint_positions: float | List[float], closed_gripper_joint_positions: float | List[float], max_effort: float = 0.0, ignore_new_calls_while_executing: bool = True, callback_group: rclpy.callback_groups.CallbackGroup | None = None, gripper_command_action_name: str = 'gripper_action_controller/gripper_command')

Bases: object

Python interface for Gripper that is controlled by GripperCommand.

close(skip_if_noop: bool = False)

Close the gripper. - skip_if_noop - No action will be performed if the gripper is not open.

force_reset_executing_state()

Force reset of internal states that block execution while ignore_new_calls_while_executing is being used. This function is applicable only in a very few edge-cases, so it should almost never be used.

property gripper_command_action_client: str
property is_closed: bool

Gripper is considered to be closed if any of the joints is outside of their open position.

property is_open: bool

Gripper is considered to be open if all of the joints are at their open position.

property joint_names: List[str]
property joint_state: sensor_msgs.msg.JointState | None
move_to_position(position: float)

Move the gripper to a specific position. - position - Desired position of the gripper.

property new_joint_state_available
open(skip_if_noop: bool = False)

Open the gripper. - skip_if_noop - No action will be performed if the gripper is already open.

reset_closed(**kwargs)

Reset into closed configuration by sending a dummy joint trajectory. This is useful for simulated robots that allow instantaneous reset of joints.

reset_open(**kwargs)

Reset into open configuration by sending a dummy joint trajectory. This is useful for simulated robots that allow instantaneous reset of joints.

toggle()

Toggles the gripper between open and closed state.

wait_until_executed() bool

Wait until the previously requested motion is finalised through either a success or failure.