Gripper

class locobot.gripper.LoCoBotGripper(configs, wait_time=3)[source]

Bases: pyrobot.core.Gripper

Interface for gripper

__init__(configs, wait_time=3)[source]

The constructor for LoCoBotGripper class.

Parameters:
  • configs (YACS CfgNode) – configurations for gripper
  • wait_time (float) – waiting time for opening/closing gripper
close(wait=True)[source]

Commands gripper to close fully

Parameters:wait (bool) – True if blocking call and will return after target_joint is achieved, False otherwise
get_gripper_state()[source]

Return the gripper state.

Returns:state

state = -1: unknown gripper state

state = 0: gripper is fully open

state = 1: gripper is closing

state = 2: there is an object in the gripper

state = 3: gripper is fully closed

Return type:int
open(wait=True)[source]

Commands gripper to open fully

Parameters:wait (bool) – True if blocking call and will return after target_joint is achieved, False otherwise
reset(wait=True)[source]

Utility function to reset gripper if it is stuck

Parameters:wait (bool) – True if blocking call and will return after target_joint is achieved, False otherwise