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

Class Gripper

source code

object --+
         |
        Gripper

Interface class for a gripper on the Intera Research Robot.

Instance Methods [hide private]
 
__init__(self, side='right', calibrate=True)
Constructor.
source code
 
_config_callback(self, msg)
config topic callback
source code
bool
reboot(self)
Power cycle the gripper, removing calibration information.
source code
bool
stop(self)
Set the gripper to stop executing command at the current position, apply holding force.
source code
bool
start(self)
Set the gripper to start executing command at the current position, apply holding force.
source code
bool
open(self, position=0.041667)
Set the gripper position to open by providing opening position.
source code
bool
close(self, position=0.0)
Set the gripper position to close by providing closing position.
source code
bool
has_error(self)
Returns a bool describing whether the gripper is in an error state.
source code
bool
is_ready(self)
Returns bool describing if the gripper ready, i.e.
source code
bool
is_moving(self)
Returns bool describing if the gripper is moving.
source code
bool
is_gripping(self)
Returns bool describing if the gripper is gripping.
source code
bool
is_calibrated(self)
Returns bool describing if the gripper is calibrated.
source code
bool
calibrate(self)
Calibrate the gripper in order to set maximum and minimum travel distance.
source code
float
get_position(self)
Returns float describing the gripper position in meters.
source code
bool
set_position(self, position)
Set the position of gripper.
source code
float
set_velocity(self, speed)
Set the velocity at which the gripper position movement will execute.
source code
float
get_force(self)
Returns the force sensed by the gripper in estimated Newtons.
source code
bool
set_holding_force(self, holding_force)
Set holding force of successful gripper grasp.
source code
bool
set_object_weight(self, object_weight)
Set the weight of the object in kilograms.
source code
bool
set_dead_zone(self, dead_zone)
Set the gripper dead zone describing the position error threshold where a move will be considered successful.
source code

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

Class Variables [hide private]
  MAX_POSITION = 0.041667
  MIN_POSITION = 0.0
  MAX_FORCE = 10.0
  MIN_FORCE = 0.0
  MAX_VELOCITY = 3.0
  MIN_VELOCITY = 0.15
Properties [hide private]

Inherited from object: __class__

Method Details [hide private]

__init__(self, side='right', calibrate=True)
(Constructor)

source code 

Constructor.

Parameters:
  • side (str) - robot gripper name
  • calibrate (bool) - Attempts to calibrate the gripper when initializing class (defaults True)
Overrides: object.__init__

reboot(self)

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.

Returns: bool
True if successfully Rebooted, False otherwise

stop(self)

source code 

Set the gripper to stop executing command at the current position, apply holding force.

Returns: bool
True if successfully Stopped, False otherwise

start(self)

source code 

Set the gripper to start executing command at the current position, apply holding force.

Returns: bool
True if successfully Started, False otherwise

open(self, position=0.041667)

source code 

Set the gripper position to open by providing opening position.

Returns: bool
True if successfully set Position, False otherwise

close(self, position=0.0)

source code 

Set the gripper position to close by providing closing position.

Returns: bool
True if successfully set Position, False otherwise

has_error(self)

source code 

Returns a bool describing whether the gripper is in an error state. (True: Error detected, False: No errors)

Returns: bool
True if in error state, False otherwise

is_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 in ready state, False otherwise

is_moving(self)

source code 

Returns bool describing if the gripper is moving.

Returns: bool
True if in moving state, False otherwise

is_gripping(self)

source code 

Returns bool describing if the gripper is gripping.

Returns: bool
True if in gripping state, False otherwise

is_calibrated(self)

source code 

Returns bool describing if the gripper is calibrated.

Returns: bool
True if successfully calibrated, False otherwise

calibrate(self)

source code 

Calibrate the gripper in order to set maximum and minimum travel distance.

Returns: bool
True if successfully calibrating, False otherwise

get_position(self)

source code 

Returns float describing the gripper position in meters.

Returns: float
Current Position value in Meters (m)

set_position(self, position)

source code 

Set the position of gripper.

Returns: bool
True if successfully set value, False otherwise

set_velocity(self, speed)

source code 

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

Returns: float
Current Velocity value in Meters / second (m/s)

get_force(self)

source code 

Returns the force sensed by the gripper in estimated Newtons.

Returns: float
Current Force value in Newton-Meters (N-m)

set_holding_force(self, holding_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.

Returns: bool
True if successfully set value, False otherwise

set_object_weight(self, object_weight)

source code 

Set the weight of the object in kilograms.

Returns: bool
True if successfully set value, False otherwise

set_dead_zone(self, dead_zone)

source code 

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

Returns: bool
True if successfully set value, False otherwise