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

Source Code for Module baxter_interface.gripper

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