Package baxter_interface :: Module gripper :: Class Gripper
[hide private]
[frames] | no frames]

Class Gripper

source code

object --+
         |
        Gripper

Interface class for a gripper on the Baxter Research Robot.

Instance Methods [hide private]
 
__init__(self, gripper, versioned=False)
Version-checking capable constructor.
source code
 
_on_gripper_state(self, state) source code
 
_on_gripper_prop(self, properties) source code
 
_inc_cmd_sequence(self) source code
 
_clip(self, val) source code
 
_capablity_warning(self, cmd) source code
 
_version_str_to_time(self, version_str, version_type) source code
bool
version_check(self)
Does a safety check on the firmware build date of the electric grippers versus the version of the SDK software.
source code
 
command(self, cmd, block=False, test=<function <lambda> at 0x18e0938>, timeout=0.0, args=None)
Raw command call to directly control gripper.
source code
str
valid_parameters_text(self)
Text describing valid gripper parameters.
source code
dict({str:float})
valid_parameters(self)
Returns dict of available gripper parameters with default parameters.
source code
 
set_parameters(self, parameters=None, defaults=False)
Set the parameters that will describe the position command execution.
source code
bool
reset_custom_properties(self, timeout=2.0)
Resets default properties for custom grippers
source code
bool
reset_custom_state(self, timeout=2.0)
Resets default state for custom grippers
source code
 
reset(self, block=True, timeout=2.0)
Resets the gripper state removing any errors.
source code
 
_cmd_reboot(self, block=True, timeout=5.0)
Power cycle the gripper, removing calibration information.
source code
 
reboot(self, timeout=5.0, delay_check=0.1)
"Clean" reboot of gripper, removes calibration and errors.
source code
 
clear_calibration(self, block=True, timeout=2.0)
Clear calibration information from gripper.
source code
bool
calibrate(self, block=True, timeout=5.0)
Calibrate the gripper setting maximum and minimum travel distance.
source code
 
stop(self, block=True, timeout=5.0)
Stop the gripper at the current position and apply holding force.
source code
 
command_position(self, position, block=False, timeout=5.0)
Command the gripper position movement.
source code
 
command_suction(self, block=False, timeout=5.0)
Command the gripper suction.
source code
 
set_velocity(self, velocity)
Set the velocity at which the gripper position movement will execute.
source code
 
set_moving_force(self, force)
Set the moving force threshold of the position move execution.
source code
 
set_holding_force(self, force)
Set holding force of successful gripper grasp.
source code
 
set_dead_band(self, dead_band)
Set the gripper dead band for position moves.
source code
 
set_vacuum_threshold(self, threshold)
Set suction threshold of successful grasp.
source code
 
set_blow_off(self, blow_off)
Sets the blow_off parameter.
source code
 
open(self, block=False, timeout=5.0)
Commands maximum gripper position.
source code
 
close(self, block=False, timeout=5.0)
Commands minimum gripper position.
source code
dict({str:float})
parameters(self)
Returns dict of parameters describing the gripper command execution.
source code
bool
calibrated(self)
Returns bool describing gripper calibration state.
source code
bool
ready(self)
Returns bool describing if the gripper ready, i.e.
source code
bool
moving(self)
Returns bool describing if the gripper is in motion
source code
bool
gripping(self)
Returns bool describing if the position move has been preempted by a position command exceeding the moving_force threshold denoting a grasp.
source code
bool
missed(self)
Returns bool describing if the position move has completed without exceeding the moving_force threshold denoting a grasp
source code
bool
error(self)
Returns bool describing if the gripper is in an error state.
source code
float
position(self)
Returns the current gripper position as a ratio (0-100) of the total gripper travel.
source code
float
force(self)
Returns the current measured gripper force as a ratio (0-100) of the total force applicable.
source code
float
vacuum_sensor(self)
Returns the value (0-100) of the current vacuum sensor reading as a percentage of the full vacuum sensor range.
source code
bool
vacuum(self)
Returns bool describing if the vacuum sensor threshold has been exceeded during a command_suction event.
source code
bool
blowing(self)
Returns bool describing if the gripper is currently blowing.
source code
bool
sucking(self)
Returns bool describing if the gripper is currently sucking.
source code
bool
has_force(self)
Returns bool describing if the gripper is capable of force control.
source code
bool
has_position(self)
Returns bool describing if the gripper is capable of position control.
source code
str
type(self)
Returns string describing the gripper type.
source code
int
hardware_id(self)
Returns unique hardware id number.
source code
str
hardware_name(self)
Returns string describing the gripper hardware.
source code
str
firmware_build_date(self)
Returns the build date of the firmware on the current gripper.
source code
str
firmware_version(self)
Returns the current gripper firmware revision.
source code

Inherited from object: __delattr__, __format__, __getattribute__, __hash__, __new__, __reduce__, __reduce_ex__, __repr__, __setattr__, __sizeof__, __str__, __subclasshook__

Properties [hide private]

Inherited from object: __class__

Method Details [hide private]

__init__(self, gripper, versioned=False)
(Constructor)

source code 

Version-checking capable constructor.

Parameters:
  • gripper (str) - robot limb <left/right> on which the gripper is mounted
  • versioned (bool) - True if Gripper firmware version should be checked on initialization. [False]

    The gripper firmware versions are checked against the version compatibility list in baxter_interface.VERSIONS_SDK2GRIPPER. The compatibility list is updated in each SDK release.

    By default, this interface class will not check versions, but all examples using Grippers in baxter_examples pass a True and will check. This behavior can be overridden by setting baxter_interface.CHECK_VERSION to False.

Overrides: object.__init__

version_check(self)

source code 

Does a safety check on the firmware build date of the electric grippers versus the version of the SDK software.

Returns: bool
True if gripper version is compatible with SDK version, including if in warning list or unknown.

False if incompatible and in fatal fail list.

command(self, cmd, block=False, test=<function <lambda> at 0x18e0938>, timeout=0.0, args=None)

source code 

Raw command call to directly control gripper.

Parameters:
  • cmd (str) - string of known gripper commands
  • block (bool) - command is blocking or non-blocking [False]
  • test (func) - test function for command validation
  • timeout (float) - timeout in seconds for command evaluation
  • args (dict({str:float})) - dictionary of parameter:value

valid_parameters_text(self)

source code 

Text describing valid gripper parameters.

Returns: str
Human readable block of text describing parameters. Good for help text.

valid_parameters(self)

source code 

Returns dict of available gripper parameters with default parameters.

Returns: dict({str:float})
valid parameters in a code-friendly dict type. Use this version in your programs.

set_parameters(self, parameters=None, defaults=False)

source code 

Set the parameters that will describe the position command execution.

Parameters:
  • parameters (dict({str:float})) - dictionary of parameter:value

    Percentage of maximum (0-100) for each parameter

reset_custom_properties(self, timeout=2.0)

source code 

Resets default properties for custom grippers

Returns: bool
True if custom gripper properties reset successfully

reset_custom_state(self, timeout=2.0)

source code 

Resets default state for custom grippers

Returns: bool
True if custom gripper state reset successfully

reset(self, block=True, timeout=2.0)

source code 

Resets the gripper state removing any errors.

Parameters:
  • timeout (float) - timeout in seconds for reset success
  • block (bool) - command is blocking or non-blocking [False]

_cmd_reboot(self, block=True, timeout=5.0)

source code 

Power cycle the gripper, removing calibration information.

Basic call to the gripper reboot command. Waits for gripper to return ready state but does not clear errors that could occur during boot. Highly recommended to use the clean reboot() command instead.

Parameters:
  • timeout (float) - timeout in seconds for reboot success
  • block (bool) - command is blocking or non-blocking [False]

reboot(self, timeout=5.0, delay_check=0.1)

source code 

"Clean" reboot of gripper, removes calibration and errors.

Robust version of gripper reboot command; recommended to use this function for rebooting grippers.

Calls the basic reboot gripper command to power cycle the gripper (_cmd_reboot()) and then checks for errors after reboot, calling reset to clear errors if needed.

Parameters:
  • timeout (float) - timeouts in seconds for reboot & reset
  • delay_check (float) - seconds after reboot before error check

clear_calibration(self, block=True, timeout=2.0)

source code 

Clear calibration information from gripper.

Allows (and requires) new gripper calibration to be run.

Parameters:
  • timeout (float) - timeout in seconds for success
  • block (bool) - command is blocking or non-blocking [False]

calibrate(self, block=True, timeout=5.0)

source code 

Calibrate the gripper setting maximum and minimum travel distance.

Parameters:
  • timeout (float) - timeout in seconds for calibration success
  • block (bool) - command is blocking or non-blocking [False]
Returns: bool
Returns True if calibration succeeds.

stop(self, block=True, timeout=5.0)

source code 

Stop the gripper at the current position and apply holding force.

Parameters:
  • timeout (float) - timeout in seconds for stop success
  • block (bool) - command is blocking or non-blocking [False]

command_position(self, position, block=False, timeout=5.0)

source code 

Command the gripper position movement.

Parameters:
  • position (float) - in % 0=close 100=open

    From minimum/closed (0.0) to maximum/open (100.0)

command_suction(self, block=False, timeout=5.0)

source code 

Command the gripper suction.

Parameters:
  • timeout (float) - Timeout describes how long the suction will be applied while trying to determine a grasp (vacuum threshold exceeded) has been achieved.
  • block (bool) - command is blocking or non-blocking [False]

set_velocity(self, velocity)

source code 

Set the velocity at which the gripper position movement will execute.

Parameters:
  • velocity (float) - in % 0=stop 100=max [50.0]

set_moving_force(self, force)

source code 

Set the moving force threshold of the position move execution.

When exceeded, the gripper will stop trying to achieve the commanded position.

Parameters:
  • force (float) - in % 0=none 100=max [30.0]

set_holding_force(self, force)

source code 

Set holding force of successful gripper grasp.

Set the force at which the gripper will continue applying after a position command has completed either from successfully achieving the commanded position, or by exceeding the moving force threshold.

Parameters:
  • force (float) - in % 0=none 100=max [30.0]

set_dead_band(self, dead_band)

source code 

Set the gripper dead band for position moves.

Set the gripper dead band describing the position error threshold where a move will be considered successful.

Parameters:
  • dead_band (float) - in % of full position [5.0]

set_vacuum_threshold(self, threshold)

source code 

Set suction threshold of successful grasp.

Set the gripper suction threshold describing the threshold at which the measured suction (vacuum achieved) must exceed to denote a successful grasp.

Parameters:
  • threshold (float) - in % of measured vacuum range [18.0]

set_blow_off(self, blow_off)

source code 

Sets the blow_off parameter.

This parameter will be used on a stop command with the suction gripper, ceasing suction and blowing air from the suction gripper for the seconds specified by this method.

Note: This blow off will only be commanded after the previous suction command returned a successful grasp (suction threshold was exceeded)

Parameters:
  • blow_off (float) - Time in seconds to blow air on release [0.4]

open(self, block=False, timeout=5.0)

source code 

Commands maximum gripper position.

Parameters:
  • block (bool) - open command is blocking or non-blocking [False]
  • timeout (float) - timeout in seconds for open command success

close(self, block=False, timeout=5.0)

source code 

Commands minimum gripper position.

Parameters:
  • block (bool) - close command is blocking or non-blocking [False]
  • timeout (float) - timeout in seconds for close command success

parameters(self)

source code 

Returns dict of parameters describing the gripper command execution.

Returns: dict({str:float})
parameters describing the gripper command execution

calibrated(self)

source code 

Returns bool describing gripper calibration state. (0:Not Calibrated, 1:Calibrated)

Returns: bool
False if Not Calibrated, True if Calibrated. Grippers that cannot calibrate should return True (i.e. "Always calibrated").

ready(self)

source code 

Returns bool describing if the gripper ready, i.e. is calibrated, not busy (as in resetting or rebooting), and not moving.

Returns: bool
True if gripper is not busy

moving(self)

source code 

Returns bool describing if the gripper is in motion

Returns: bool
True if gripper is in motion

error(self)

source code 

Returns bool describing if the gripper is in an error state.

Error states can be caused by over/undervoltage, over/under current, motor faults, etc.

Errors can be cleared with a gripper reset. If persistent please contact Rethink Robotics for further debugging.

Returns: bool

vacuum_sensor(self)

source code 

Returns the value (0-100) of the current vacuum sensor reading as a percentage of the full vacuum sensor range.

The message field contains an 8-bit integer representation of the vacuum sensor, this function converts that integer to the percentage of the full sensor range.

Returns: float

type(self)

source code 

Returns string describing the gripper type.

Known types are 'suction', 'electric', and 'custom'. An unknown or no gripper attached to the research robot will be reported as 'custom'.

Returns: str

hardware_id(self)

source code 

Returns unique hardware id number. This is required for sending commands to the gripper.

Returns: int