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

Source Code for Module baxter_interface.gripper

  1  # Copyright (c) 2013-2014, Rethink Robotics 
  2  # All rights reserved. 
  3  # 
  4  # Redistribution and use in source and binary forms, with or without 
  5  # modification, are permitted provided that the following conditions are met: 
  6  # 
  7  # 1. Redistributions of source code must retain the above copyright notice, 
  8  #    this list of conditions and the following disclaimer. 
  9  # 2. Redistributions in binary form must reproduce the above copyright 
 10  #    notice, this list of conditions and the following disclaimer in the 
 11  #    documentation and/or other materials provided with the distribution. 
 12  # 3. Neither the name of the Rethink Robotics nor the names of its 
 13  #    contributors may be used to endorse or promote products derived from 
 14  #    this software without specific prior written permission. 
 15  # 
 16  # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
 17  # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
 18  # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 
 19  # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 
 20  # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 
 21  # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
 22  # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
 23  # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
 24  # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
 25  # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
 26  # POSSIBILITY OF SUCH DAMAGE. 
 27   
 28  import re 
 29  import sys 
 30   
 31  from copy import deepcopy 
 32  from math import fabs 
 33   
 34  from json import ( 
 35      JSONDecoder, 
 36      JSONEncoder, 
 37  ) 
 38   
 39  import rospy 
 40   
 41  import baxter_dataflow 
 42   
 43  from baxter_core_msgs.msg import ( 
 44      EndEffectorCommand, 
 45      EndEffectorProperties, 
 46      EndEffectorState, 
 47  ) 
 48  from baxter_interface import settings 
 49   
 50   
51 -class Gripper(object):
52 """ 53 Interface class for a gripper on the Baxter Research Robot. 54 """
55 - def __init__(self, gripper, versioned=False):
56 """ 57 Version-checking capable constructor. 58 59 @type gripper: str 60 @param gripper: robot limb <left/right> on which the gripper 61 is mounted 62 @type versioned: bool 63 @param versioned: True if Gripper firmware version should be checked 64 on initialization. [False] 65 66 The gripper firmware versions are checked against the version 67 compatibility list in L{baxter_interface.VERSIONS_SDK2GRIPPER}. 68 The compatibility list is updated in each SDK release. 69 70 By default, this interface class will not check versions, 71 but all examples using Grippers in baxter_examples pass a True 72 and will check. This behavior can be overridden by setting 73 L{baxter_interface.CHECK_VERSION} to False. 74 """ 75 self.name = gripper + '_gripper' 76 self._cmd_sender = rospy.get_name() + '_%s' 77 self._cmd_sequence = 0 78 79 ns = 'robot/end_effector/' + self.name + "/" 80 81 self._state = None 82 self._prop = EndEffectorProperties(id=-1) # initialize w/unused value 83 self.on_type_changed = baxter_dataflow.Signal() 84 self.on_gripping_changed = baxter_dataflow.Signal() 85 self.on_moving_changed = baxter_dataflow.Signal() 86 87 self._parameters = dict() 88 89 self._cmd_pub = rospy.Publisher(ns + 'command', EndEffectorCommand) 90 91 self._prop_pub = rospy.Publisher(ns + 'rsdk/set_properties', 92 EndEffectorProperties, 93 latch=True 94 ) 95 96 self._state_pub = rospy.Publisher(ns + 'rsdk/set_state', 97 EndEffectorState, 98 latch=True 99 ) 100 101 self._state_sub = rospy.Subscriber(ns + 'state', 102 EndEffectorState, 103 self._on_gripper_state 104 ) 105 106 self._prop_sub = rospy.Subscriber(ns + 'properties', 107 EndEffectorProperties, 108 self._on_gripper_prop 109 ) 110 111 # Wait for the gripper state message to be populated 112 baxter_dataflow.wait_for( 113 lambda: not self._state is None, 114 timeout=5.0, 115 timeout_msg=("Failed to get state from %s" % 116 (ns + 'state',)) 117 ) 118 119 # Wait for the gripper type to be populated 120 baxter_dataflow.wait_for( 121 lambda: not self.type() is None, 122 timeout=5.0, 123 timeout_msg=("Failed to get properties from %s" % 124 (ns + 'properties',)) 125 ) 126 127 if versioned and self.type() == 'electric': 128 if not self.version_check(): 129 sys.exit(1) 130 131 self.set_parameters(defaults=True)
132
133 - def _on_gripper_state(self, state):
134 old_state = self._state 135 self._state = deepcopy(state) 136 if old_state is not None and old_state.gripping != state.gripping: 137 self.on_gripping_changed(state.gripping == True) 138 if old_state is not None and old_state.moving != state.moving: 139 self.on_moving_changed(state.moving == True)
140
141 - def _on_gripper_prop(self, properties):
142 old_prop = self._prop 143 self._prop = deepcopy(properties) 144 if old_prop.ui_type != self._prop.ui_type and old_prop.id != -1: 145 self.on_type_changed({ 146 EndEffectorProperties.SUCTION_CUP_GRIPPER: 'suction', 147 EndEffectorProperties.ELECTRIC_GRIPPER: 'electric', 148 EndEffectorProperties.CUSTOM_GRIPPER: 'custom', 149 }.get(properties.ui_type, None))
150
151 - def _inc_cmd_sequence(self):
152 # manage roll over with safe value (maxint) 153 self._cmd_sequence = (self._cmd_sequence % 0x7FFFFFFF) + 1 154 return self._cmd_sequence
155
156 - def _clip(self, val):
157 return max(min(val, 100.0), 0.0)
158
159 - def _capablity_warning(self, cmd):
160 msg = ("%s %s - not capable of '%s' command" % 161 (self.name, self.type(), cmd)) 162 rospy.logwarn(msg)
163
164 - def version_check(self):
165 """ 166 Does a safety check on the firmware version running on electric 167 grippers versus the version of the SDK software. 168 169 @rtype: bool 170 @return: True if gripper version is compatible with SDK version, 171 including if in warning list or unknown. 172 173 False if incompatible and in fatal fail list. 174 """ 175 sdk_version = settings.SDK_VERSION 176 firmware_str = self.firmware_version() 177 178 if self.type() != 'electric': 179 rospy.logwarn("%s %s (%s): Version Check not needed", 180 self.name, self.type(), firmware_str) 181 return True 182 if not firmware_str: 183 rospy.logerr("%s %s: Failed to retrieve valid version during" 184 " Version Check.", self.name, self.type()) 185 return False 186 187 # parse out tags 188 grip_version = firmware_str.split()[0] 189 190 def is_match(spec, grip): 191 if spec == grip: 192 return True 193 194 pattern = ("([0-9x]+)\.([0-9x]+)\.([0-9x]+)" 195 "($|_(alpha|beta|pre|rc|p)([0-9]+))") 196 grip_match = re.search(pattern, grip) 197 spec_match = re.search(pattern, spec) 198 if not grip_match or not spec_match: 199 if not spec_match: 200 rospy.logerr("Bad Gripper Version Spec: %s", spec) 201 return False 202 rospy.logwarn("%s %s: Version Check invalid gripper " 203 "version formats: %s for %s", 204 self.name, self.type(), firmware_str, spec) 205 return False 206 for i in range(1, 4): 207 if (grip_match.group(i) != spec_match.group(i) 208 and spec_match.group(i) != 'x'): 209 return False 210 return True
211 212 if any(is_match(sdk, grip_version) for sdk 213 in settings.VERSIONS_SDK2GRIPPER[sdk_version]['ok']): 214 return True 215 elif any(is_match(sdk, grip_version) for sdk 216 in settings.VERSIONS_SDK2GRIPPER[sdk_version]['warn']): 217 rospy.logwarn("%s %s: Gripper Firmware version (%s) is not up-to" 218 "-date for SDK Version (%s). Please use the " 219 "Robot's Field-Service-Menu to Upgrade your " 220 "Gripper Firmware.", 221 self.name, self.type(), firmware_str, sdk_version) 222 return True 223 elif any(is_match(sdk, grip_version) for sdk 224 in settings.VERSIONS_SDK2GRIPPER[sdk_version]['fail']): 225 rospy.logerr("%s %s: Gripper Firmware version (%s) is " 226 "*incompatible* with SDK Version (%s). Please use " 227 "the Robot's Field-Service-Menu to Upgrade your " 228 "Gripper Firmware.", 229 self.name, self.type(), firmware_str, sdk_version) 230 return False 231 else: 232 rospy.logwarn("%s %s: Gripper Firmware version (%s) does not " 233 "match SDK Version (%s). Use the Robot's Field-" 234 "Service-Menu to Upgrade your Gripper Firmware.", 235 self.name, self.type(), firmware_str, sdk_version) 236 return True
237
238 - def command(self, cmd, block=False, test=lambda: True, 239 timeout=0.0, args=None):
240 """ 241 Raw command call to directly control gripper. 242 243 @type cmd: str 244 @param cmd: string of known gripper commands 245 @type block: bool 246 @param block: command is blocking or non-blocking [False] 247 @type test: func 248 @param test: test function for command validation 249 @type timeout: float 250 @param timeout: timeout in seconds for command evaluation 251 @type args: dict({str:float}) 252 @param args: dictionary of parameter:value 253 """ 254 ee_cmd = EndEffectorCommand() 255 ee_cmd.id = self.hardware_id() 256 ee_cmd.command = cmd 257 ee_cmd.sender = self._cmd_sender % (cmd,) 258 ee_cmd.sequence = self._inc_cmd_sequence() 259 ee_cmd.args = '' 260 if args != None: 261 ee_cmd.args = JSONEncoder().encode(args) 262 seq_test = lambda: (self._state.command_sender == ee_cmd.sender and 263 (self._state.command_sequence == ee_cmd.sequence 264 or self._state.command_sequence == 0)) 265 self._cmd_pub.publish(ee_cmd) 266 if block: 267 finish_time = rospy.get_time() + timeout 268 cmd_seq = baxter_dataflow.wait_for( 269 test=seq_test, 270 timeout=timeout, 271 raise_on_error=False, 272 body=lambda: self._cmd_pub.publish(ee_cmd) 273 ) 274 if not cmd_seq: 275 seq_msg = (("Timed out on gripper command acknowledgement for" 276 " %s:%s") % (self.name, ee_cmd.command)) 277 rospy.logdebug(seq_msg) 278 time_remain = max(0.5, finish_time - rospy.get_time()) 279 return baxter_dataflow.wait_for( 280 test=test, 281 timeout=time_remain, 282 raise_on_error=False, 283 body=lambda: self._cmd_pub.publish(ee_cmd) 284 ) 285 else: 286 return True
287
288 - def valid_parameters_text(self):
289 """ 290 Text describing valid gripper parameters. 291 292 @rtype: str 293 @return: Human readable block of text describing parameters. 294 Good for help text. 295 """ 296 if self.type() == 'electric': 297 return """Valid gripper parameters for the electric gripper are 298 PARAMETERS: 299 velocity - Velocity at which a position move will execute 300 moving_force - Force threshold at which a move will stop 301 holding_force - Force at which a grasp will continue holding 302 dead_zone - Position deadband within move considered successful 303 ALL PARAMETERS (0-100) 304 """ 305 elif self.type() == 'suction': 306 return """Valid gripper parameters for the suction gripper are 307 PARAMETERS: 308 vacuum_sensor_threshold - Measured suction threshold denoting grasp 309 blow_off_seconds - Time in seconds to blow air on release 310 ALL PARAMETERS (0-100) 311 """ 312 else: 313 return "No valid parameters for %s %s." % (self.type(), self.name)
314
315 - def valid_parameters(self):
316 """ 317 Returns dict of available gripper parameters with default parameters. 318 319 @rtype: dict({str:float}) 320 @return: valid parameters in a code-friendly dict type. 321 Use this version in your programs. 322 """ 323 valid = dict() 324 if self.type() == 'electric': 325 valid = dict({'velocity': 50.0, 326 'moving_force': 40.0, 327 'holding_force': 30.0, 328 'dead_zone': 5.0, 329 }) 330 elif self.type() == 'suction': 331 valid = dict({'vacuum_sensor_threshold': 18.0, 332 'blow_off_seconds': 0.4, 333 }) 334 return valid
335
336 - def set_parameters(self, parameters=None, defaults=False):
337 """ 338 Set the parameters that will describe the position command execution. 339 340 @type parameters: dict({str:float}) 341 @param parameters: dictionary of parameter:value 342 343 Percentage of maximum (0-100) for each parameter 344 """ 345 valid_parameters = self.valid_parameters() 346 if defaults: 347 self._parameters = valid_parameters 348 if parameters is None: 349 parameters = dict() 350 for key in parameters.keys(): 351 if key in valid_parameters.keys(): 352 self._parameters[key] = parameters[key] 353 else: 354 msg = ("Invalid parameter: %s provided. %s" % 355 (key, self.valid_parameters_text(),)) 356 rospy.logwarn(msg) 357 cmd = EndEffectorCommand.CMD_CONFIGURE 358 self.command(cmd, args=self._parameters)
359
360 - def reset_custom_properties(self, timeout=2.0):
361 """ 362 Resets default properties for custom grippers 363 364 @return: True if custom gripper properties reset successfully 365 @rtype: bool 366 """ 367 default_id = 131073 368 default_ui_type = EndEffectorProperties.CUSTOM_GRIPPER 369 default_manufacturer = 'Rethink Research Robot' 370 default_product = 'SDK End Effector' 371 # Create default properties message 372 prop_msg = EndEffectorProperties( 373 id=default_id, 374 ui_type=default_ui_type, 375 manufacturer=default_manufacturer, 376 product=default_product, 377 ) 378 for idx, attr in enumerate(prop_msg.__slots__): 379 if prop_msg._slot_types[idx] == 'bool': 380 setattr(prop_msg, attr, True) 381 self._prop_pub.publish(prop_msg) 382 383 # Verify properties reset successfully 384 test = lambda: (self._prop.id == default_id and 385 self._prop.ui_type == default_ui_type and 386 self._prop.manufacturer == default_manufacturer and 387 self._prop.product == default_product 388 ) 389 return baxter_dataflow.wait_for( 390 test=test, 391 timeout=timeout, 392 raise_on_error=False, 393 body=lambda: self._prop_pub.publish(prop_msg) 394 )
395
396 - def reset_custom_state(self, timeout=2.0):
397 """ 398 Resets default state for custom grippers 399 400 @return: True if custom gripper state reset successfully 401 @rtype: bool 402 """ 403 state_true = EndEffectorState.STATE_TRUE 404 state_unknown = EndEffectorState.STATE_UNKNOWN 405 # Create default state message 406 state_msg = EndEffectorState() 407 for idx, attr in enumerate(state_msg.__slots__): 408 if 'int' in state_msg._slot_types[idx]: 409 setattr(state_msg, attr, state_unknown) 410 setattr(state_msg, 'enabled', state_true) 411 self._state_pub.publish(state_msg) 412 413 # Verify state reset successfully 414 test = lambda: (self._state.enabled == state_true and 415 self._state.calibrated == state_unknown and 416 self._state.ready == state_unknown and 417 self._state.position == 0.0 418 ) 419 return baxter_dataflow.wait_for( 420 test=test, 421 timeout=timeout, 422 raise_on_error=False, 423 body=lambda: self._state_pub.publish(state_msg) 424 )
425
426 - def reset(self, block=True, timeout=2.0):
427 """ 428 Resets the gripper state removing any errors. 429 430 @type timeout: float 431 @param timeout: timeout in seconds for reset success 432 @type block: bool 433 @param block: command is blocking or non-blocking [False] 434 """ 435 if self.type() != 'electric': 436 return self._capablity_warning('reset') 437 438 cmd = EndEffectorCommand.CMD_RESET 439 return self.command( 440 cmd, 441 block, 442 test=lambda: (self._state.error == False and 443 self._state.ready == True), 444 timeout=timeout, 445 )
446
447 - def _cmd_reboot(self, block=True, timeout=5.0):
448 """ 449 Power cycle the gripper, removing calibration information. 450 451 Basic call to the gripper reboot command. Waits for gripper to return 452 ready state but does not clear errors that could occur during boot. 453 Highly recommended to use the clean reboot() command instead. 454 455 @type timeout: float 456 @param timeout: timeout in seconds for reboot success 457 @type block: bool 458 @param block: command is blocking or non-blocking [False] 459 """ 460 if self.type() != 'electric': 461 return self._capablity_warning('reboot') 462 463 cmd = EndEffectorCommand.CMD_REBOOT 464 success = self.command( 465 cmd, 466 block, 467 test=lambda: (self._state.enabled == True and 468 self._state.ready == True), 469 timeout=timeout 470 ) 471 rospy.sleep(1.0) # Allow extra time for reboot to complete 472 self.set_parameters(defaults=True) 473 return success
474
475 - def reboot(self, timeout=5.0, delay_check=0.1):
476 """ 477 "Clean" reboot of gripper, removes calibration and errors. 478 479 Robust version of gripper reboot command; recommended to use this 480 function for rebooting grippers. 481 482 Calls the basic reboot gripper command to power cycle the gripper 483 (_cmd_reboot()) and then checks for errors after reboot, calling 484 reset to clear errors if needed. 485 486 @type timeout: float 487 @param timeout: timeouts in seconds for reboot & reset 488 @type delay_check: float 489 @param delay_check: seconds after reboot before error check 490 """ 491 if self.type() != 'electric': 492 return self._capablity_warning('reboot') 493 494 self._cmd_reboot(block=True, timeout=timeout) 495 rospy.sleep(delay_check) 496 if self.error(): 497 if not self.reset(block=True, timeout=timeout): 498 rospy.logerr("Failed to reset gripper error after reboot.") 499 return False 500 self.set_parameters(defaults=True) 501 return True
502
503 - def clear_calibration(self, block=True, timeout=2.0):
504 """ 505 Clear calibration information from gripper. 506 507 Allows (and requires) new gripper calibration to be run. 508 509 @type timeout: float 510 @param timeout: timeout in seconds for success 511 @type block: bool 512 @param block: command is blocking or non-blocking [False] 513 """ 514 if self.type() != 'electric': 515 return self._capablity_warning('clear_calibration') 516 517 cmd = EndEffectorCommand.CMD_CLEAR_CALIBRATION 518 return self.command( 519 cmd, 520 block, 521 test=lambda: (self._state.calibrated == False and 522 self._state.ready == True), 523 timeout=timeout 524 )
525
526 - def calibrate(self, block=True, timeout=5.0):
527 """ 528 Calibrate the gripper setting maximum and minimum travel distance. 529 530 @type timeout: float 531 @param timeout: timeout in seconds for calibration success 532 @type block: bool 533 @param block: command is blocking or non-blocking [False] 534 @rtype: bool 535 @return: Returns True if calibration succeeds. 536 """ 537 if self.type() != 'electric': 538 return self._capablity_warning('calibrate') 539 540 # clear any previous calibration and any current errors 541 if self.calibrated(): 542 self.clear_calibration() 543 if self.error(): 544 self.reset(block=block) 545 546 cmd = EndEffectorCommand.CMD_CALIBRATE 547 success = self.command( 548 cmd, 549 block, 550 test=lambda: (self._state.calibrated == True and 551 self._state.ready == True), 552 timeout=timeout 553 ) 554 self.set_parameters(defaults=True) 555 return success
556
557 - def stop(self, block=True, timeout=5.0):
558 """ 559 Stop the gripper at the current position and apply holding force. 560 561 @type timeout: float 562 @param timeout: timeout in seconds for stop success 563 @type block: bool 564 @param block: command is blocking or non-blocking [False] 565 """ 566 if self.type() == 'custom': 567 return self._capablity_warning('stop') 568 569 if self.type() == 'electric': 570 cmd = EndEffectorCommand.CMD_STOP 571 stop_test = lambda: self._state.moving == False 572 elif self.type() == 'suction': 573 timeout = max(self._parameters['blow_off_seconds'], timeout) 574 cmd = EndEffectorCommand.CMD_RELEASE 575 stop_test = lambda: (not self.sucking() and not self.blowing()) 576 return self.command( 577 cmd, 578 block, 579 test=stop_test, 580 timeout=timeout, 581 )
582
583 - def command_position(self, position, block=False, timeout=5.0):
584 """ 585 Command the gripper position movement. 586 587 @type position: float 588 @param position: in % 0=close 100=open 589 590 From minimum/closed (0.0) to maximum/open (100.0) 591 """ 592 if self.type() == 'custom': 593 return self._capablity_warning('command_position') 594 595 if self._state.calibrated != True: 596 msg = "Unable to command %s position until calibrated" % self.name 597 rospy.logwarn(msg) 598 return False 599 600 cmd = EndEffectorCommand.CMD_GO 601 arguments = {"position": self._clip(position)} 602 if self.type() == 'electric': 603 cmd_test = lambda: ((fabs(self._state.position - position) 604 < self._parameters['dead_zone']) 605 or self._state.gripping == True) 606 return self.command( 607 cmd, 608 block, 609 test=cmd_test, 610 timeout=timeout, 611 args=arguments 612 ) 613 elif arguments['position'] < 100.0: 614 return self.close(block=block, timeout=timeout) 615 else: 616 return self.open(block=block, timeout=timeout)
617
618 - def command_suction(self, block=False, timeout=5.0):
619 """ 620 Command the gripper suction. 621 622 @type timeout: float 623 @param timeout: Timeout describes how long the suction will be 624 applied while trying to determine a grasp (vacuum threshold exceeded) 625 has been achieved. 626 627 @type block: bool 628 @param block: command is blocking or non-blocking [False] 629 """ 630 if self.type() != 'suction': 631 return self._capablity_warning('command_suction') 632 633 cmd = EndEffectorCommand.CMD_GO 634 arguments = {"grip_attempt_seconds": timeout} 635 return self.command( 636 cmd, 637 block, 638 test=self.vacuum, 639 timeout=timeout, 640 args=arguments, 641 )
642
643 - def set_velocity(self, velocity):
644 """ 645 Set the velocity at which the gripper position movement will execute. 646 647 @type velocity: float 648 @param velocity: in % 0=stop 100=max [50.0] 649 """ 650 if self.type() != 'electric': 651 return self._capablity_warning('set_velocity') 652 653 velocity_param = dict(velocity=self._clip(velocity)) 654 self.set_parameters(parameters=velocity_param, defaults=False)
655
656 - def set_moving_force(self, force):
657 """ 658 Set the moving force threshold of the position move execution. 659 660 When exceeded, the gripper will stop trying to achieve the commanded 661 position. 662 663 @type force: float 664 @param force: in % 0=none 100=max [30.0] 665 """ 666 if self.type() != 'electric': 667 return self._capablity_warning('set_moving_force') 668 669 moving = dict(moving_force=self._clip(force)) 670 self.set_parameters(parameters=moving, defaults=False)
671
672 - def set_holding_force(self, force):
673 """ 674 Set holding force of successful gripper grasp. 675 676 Set the force at which the gripper will continue applying after a 677 position command has completed either from successfully achieving the 678 commanded position, or by exceeding the moving force threshold. 679 680 @type force: float 681 @param force: in % 0=none 100=max [30.0] 682 """ 683 if self.type() != 'electric': 684 return self._capablity_warning('set_holding_force') 685 686 holding = dict(holding_force=self._clip(force)) 687 self.set_parameters(parameters=holding, defaults=False)
688
689 - def set_dead_band(self, dead_band):
690 """ 691 Set the gripper dead band for position moves. 692 693 Set the gripper dead band describing the position error threshold 694 where a move will be considered successful. 695 696 @type dead_band: float 697 @param dead_band: in % of full position [5.0] 698 """ 699 if self.type() != 'electric': 700 return self._capablity_warning('set_dead_band') 701 702 dead_band_param = dict(dead_zone=self._clip(dead_band)) 703 self.set_parameters(parameters=dead_band_param, defaults=False)
704
705 - def set_vacuum_threshold(self, threshold):
706 """ 707 Set suction threshold of successful grasp. 708 709 Set the gripper suction threshold describing the threshold at which 710 the measured suction (vacuum achieved) must exceed to denote a 711 successful grasp. 712 713 @type threshold: float 714 @param threshold: in % of measured vacuum range [18.0] 715 """ 716 if self.type() != 'suction': 717 return self._capablity_warning('set_vacuum_threshold') 718 719 threshold_param = dict(vacuum_sensor_threshold=self._clip(threshold)) 720 self.set_parameters(parameters=threshold_param, defaults=False)
721
722 - def set_blow_off(self, blow_off):
723 """ 724 Sets the blow_off parameter. 725 726 This parameter will be used on a stop 727 command with the suction gripper, ceasing suction and blowing air 728 from the suction gripper for the seconds specified by this method. 729 730 Note: This blow off will only be commanded after the previous suction 731 command returned a successful grasp (suction threshold was exceeded) 732 733 @type blow_off: float 734 @param blow_off: Time in seconds to blow air on release [0.4] 735 """ 736 if self.type() != 'suction': 737 return self._capablity_warning('set_blow_off') 738 739 blow_off_param = dict(blow_off_seconds=blow_off) 740 self.set_parameters(parameters=blow_off_param, defaults=False)
741
742 - def open(self, block=False, timeout=5.0):
743 """ 744 Commands maximum gripper position. 745 746 @type block: bool 747 @param block: open command is blocking or non-blocking [False] 748 @type timeout: float 749 @param timeout: timeout in seconds for open command success 750 """ 751 if self.type() == 'custom': 752 return self._capablity_warning('open') 753 elif self.type() == 'electric': 754 return self.command_position(position=100.0, block=block, 755 timeout=timeout) 756 elif self.type() == 'suction': 757 return self.stop(block=block, timeout=timeout)
758
759 - def close(self, block=False, timeout=5.0):
760 """ 761 Commands minimum gripper position. 762 763 @type block: bool 764 @param block: close command is blocking or non-blocking [False] 765 @type timeout: float 766 @param timeout: timeout in seconds for close command success 767 """ 768 if self.type() == 'custom': 769 return self._capablity_warning('close') 770 elif self.type() == 'electric': 771 return self.command_position(position=0.0, block=block, 772 timeout=timeout) 773 elif self.type() == 'suction': 774 return self.command_suction(block=block, timeout=timeout)
775
776 - def parameters(self):
777 """ 778 Returns dict of parameters describing the gripper command execution. 779 780 @rtype: dict({str:float}) 781 @return: parameters describing the gripper command execution 782 """ 783 return deepcopy(self._parameters)
784
785 - def calibrated(self):
786 """ 787 Returns bool describing gripper calibration state. 788 (0:Not Calibrated, 1:Calibrated) 789 790 @rtype: bool 791 @return: False if Not Calibrated, True if Calibrated. 792 Grippers that cannot calibrate should return True 793 (i.e. "Always calibrated"). 794 """ 795 return self._state.calibrated == True
796
797 - def ready(self):
798 """ 799 Returns bool describing if the gripper ready, i.e. is calibrated, not 800 busy (as in resetting or rebooting), and not moving. 801 802 @rtype: bool 803 @return: True if gripper is not busy 804 """ 805 return self._state.ready == True
806
807 - def moving(self):
808 """ 809 Returns bool describing if the gripper is in motion 810 811 @rtype: bool 812 @return: True if gripper is in motion 813 """ 814 return self._state.moving == True
815
816 - def gripping(self):
817 """ 818 Returns bool describing if the position move has been preempted by a 819 position command exceeding the moving_force threshold denoting a grasp. 820 821 @rtype: bool 822 """ 823 return self._state.gripping == True
824
825 - def missed(self):
826 """ 827 Returns bool describing if the position move has completed without 828 exceeding the moving_force threshold denoting a grasp 829 830 @rtype: bool 831 """ 832 return self._state.missed == True
833
834 - def error(self):
835 """ 836 Returns bool describing if the gripper is in an error state. 837 838 Error states can be caused by over/undervoltage, over/under current, 839 motor faults, etc. 840 841 Errors can be cleared with a gripper reset. If persistent please 842 contact Rethink Robotics for further debugging. 843 844 @rtype: bool 845 """ 846 return self._state.error == True
847
848 - def position(self):
849 """ 850 Returns the current gripper position as a ratio (0-100) of the total 851 gripper travel. 852 853 @rtype: float 854 """ 855 return deepcopy(self._state.position)
856
857 - def force(self):
858 """ 859 Returns the current measured gripper force as a ratio (0-100) of the 860 total force applicable. 861 862 @rtype: float 863 """ 864 return deepcopy(self._state.force)
865
866 - def vacuum_sensor(self):
867 """ 868 Returns the value (0-100) of the current vacuum sensor reading as a 869 percentage of the full vacuum sensor range. 870 871 The message field contains an 8-bit integer representation of the 872 vacuum sensor, this function converts that integer to the percentage of 873 the full sensor range. 874 875 @rtype: float 876 """ 877 if self.type() != 'suction': 878 return self._capablity_warning('vacuum_sensor') 879 sensor = JSONDecoder().decode(self._state.state)['vacuum sensor'] 880 return (sensor / 255.0) * 100.0
881
882 - def vacuum(self):
883 """ 884 Returns bool describing if the vacuum sensor threshold has been 885 exceeded during a command_suction event. 886 887 @rtype: bool 888 """ 889 if self.type() != 'suction': 890 return self._capablity_warning('vacuum') 891 return JSONDecoder().decode(self._state.state)['vacuum']
892
893 - def blowing(self):
894 """ 895 Returns bool describing if the gripper is currently blowing. 896 897 @rtype: bool 898 """ 899 if self.type() != 'suction': 900 return self._capablity_warning('blowing') 901 return JSONDecoder().decode(self._state.state)['blowing']
902
903 - def sucking(self):
904 """ 905 Returns bool describing if the gripper is currently sucking. 906 907 @rtype: bool 908 """ 909 if self.type() != 'suction': 910 return self._capablity_warning('sucking') 911 return JSONDecoder().decode(self._state.state)['sucking']
912
913 - def has_force(self):
914 """ 915 Returns bool describing if the gripper is capable of force control. 916 917 @rtype: bool 918 """ 919 return self._prop.controls_force == True
920
921 - def has_position(self):
922 """ 923 Returns bool describing if the gripper is capable of position control. 924 925 @rtype: bool 926 """ 927 return self._prop.controls_position == True
928
929 - def type(self):
930 """ 931 Returns string describing the gripper type. 932 933 Known types are 'suction', 'electric', and 'custom'. An unknown or no 934 gripper attached to the research robot will be reported as 'custom'. 935 936 @rtype: str 937 """ 938 return { 939 EndEffectorProperties.SUCTION_CUP_GRIPPER: 'suction', 940 EndEffectorProperties.ELECTRIC_GRIPPER: 'electric', 941 EndEffectorProperties.CUSTOM_GRIPPER: 'custom', 942 }.get(self._prop.ui_type, None)
943
944 - def hardware_id(self):
945 """ 946 Returns unique hardware id number. This is required for sending 947 commands to the gripper. 948 949 @rtype: int 950 """ 951 return deepcopy(self._state.id)
952
953 - def hardware_version(self):
954 """ 955 [DEPRECATED: renamed to hardware_name()] 956 957 Returns string describing the gripper hardware. 958 """ 959 rospy.logwarn("Function baxter_interface.Gripper.hardware_version()" 960 " will be deprecated in next release. Please use" 961 " Gripper.hardware_name() instead.") 962 return self.hardware_name()
963
964 - def hardware_name(self):
965 """ 966 Returns string describing the gripper hardware. 967 968 @rtype: str 969 """ 970 return deepcopy(self._prop.product)
971
972 - def firmware_version(self):
973 """ 974 Returns the current gripper firmware revision. 975 976 @rtype: str 977 """ 978 return deepcopy(self._prop.firmware_rev)
979