tuck_arms.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 """
00031 Tool to tuck/untuck Baxter's arms to/from the shipping pose
00032 """
00033 import argparse
00034 
00035 from copy import deepcopy
00036 
00037 import rospy
00038 
00039 from std_msgs.msg import (
00040     Empty,
00041     Bool,
00042 )
00043 
00044 import baxter_interface
00045 
00046 from baxter_core_msgs.msg import (
00047     CollisionAvoidanceState,
00048 )
00049 from baxter_interface import CHECK_VERSION
00050 
00051 
00052 class Tuck(object):
00053     def __init__(self, tuck_cmd):
00054         self._done = False
00055         self._limbs = ('left', 'right')
00056         self._arms = {
00057             'left': baxter_interface.Limb('left'),
00058             'right': baxter_interface.Limb('right'),
00059             }
00060         self._tuck = tuck_cmd
00061         self._tuck_rate = rospy.Rate(20.0)  # Hz
00062         self._tuck_threshold = 0.2  # radians
00063         self._peak_angle = -1.6  # radians
00064         self._arm_state = {
00065                            'tuck': {'left': 'none', 'right': 'none'},
00066                            'collide': {'left': False, 'right': False},
00067                            'flipped': {'left': False, 'right': False}
00068                           }
00069         self._joint_moves = {
00070             'tuck': {
00071                      'left':  [-1.0, -2.07,  3.0, 2.55,  0.0, 0.01,  0.0],
00072                      'right':  [1.0, -2.07, -3.0, 2.55, -0.0, 0.01,  0.0]
00073                      },
00074             'untuck': {
00075                        'left':  [-0.08, -1.0, -1.19, 1.94,  0.67, 1.03, -0.50],
00076                        'right':  [0.08, -1.0,  1.19, 1.94, -0.67, 1.03,  0.50]
00077                        }
00078             }
00079         self._collide_lsub = rospy.Subscriber(
00080                              'robot/limb/left/collision_avoidance_state',
00081                              CollisionAvoidanceState,
00082                              self._update_collision, 'left')
00083         self._collide_rsub = rospy.Subscriber(
00084                              'robot/limb/right/collision_avoidance_state',
00085                              CollisionAvoidanceState,
00086                              self._update_collision, 'right')
00087         self._disable_pub = {
00088             'left': rospy.Publisher(
00089                  'robot/limb/left/suppress_collision_avoidance',
00090                  Empty, queue_size=10),
00091             'right': rospy.Publisher(
00092                  'robot/limb/right/suppress_collision_avoidance',
00093                  Empty, queue_size=10)
00094         }
00095         self._rs = baxter_interface.RobotEnable(CHECK_VERSION)
00096         self._enable_pub = rospy.Publisher('robot/set_super_enable', 
00097                                            Bool, queue_size=10)
00098 
00099     def _update_collision(self, data, limb):
00100         self._arm_state['collide'][limb] = len(data.collision_object) > 0
00101         self._check_arm_state()
00102 
00103     def _check_arm_state(self):
00104         """
00105         Check for goals and behind collision field.
00106 
00107         If s1 joint is over the peak, collision will need to be disabled
00108         to get the arm around the head-arm collision force-field.
00109         """
00110         diff_check = lambda a, b: abs(a - b) <= self._tuck_threshold
00111         for limb in self._limbs:
00112             angles = [self._arms[limb].joint_angle(joint)
00113                       for joint in self._arms[limb].joint_names()]
00114 
00115             # Check if in a goal position
00116             untuck_goal = map(diff_check, angles,
00117                               self._joint_moves['untuck'][limb])
00118             tuck_goal = map(diff_check, angles[0:2],
00119                             self._joint_moves['tuck'][limb][0:2])
00120             if all(untuck_goal):
00121                 self._arm_state['tuck'][limb] = 'untuck'
00122             elif all(tuck_goal):
00123                 self._arm_state['tuck'][limb] = 'tuck'
00124             else:
00125                 self._arm_state['tuck'][limb] = 'none'
00126 
00127             # Check if shoulder is flipped over peak
00128             self._arm_state['flipped'][limb] = (
00129                 self._arms[limb].joint_angle(limb + '_s1') <= self._peak_angle)
00130 
00131     def _prepare_to_tuck(self):
00132         # If arms are in "tucked" state, disable collision avoidance
00133         # before enabling robot, to avoid arm jerking from "force-field".
00134         head = baxter_interface.Head()
00135         start_disabled = not self._rs.state().enabled
00136         at_goal = lambda: (abs(head.pan()) <=
00137                         baxter_interface.settings.HEAD_PAN_ANGLE_TOLERANCE)
00138 
00139         rospy.loginfo("Moving head to neutral position")
00140         while not at_goal() and not rospy.is_shutdown():
00141             if start_disabled:
00142                 [pub.publish(Empty()) for pub in self._disable_pub.values()]
00143             if not self._rs.state().enabled:
00144                 self._enable_pub.publish(True)
00145             head.set_pan(0.0, 50.0, timeout=0)
00146             self._tuck_rate.sleep()
00147 
00148         if start_disabled:
00149             while self._rs.state().enabled == True and not rospy.is_shutdown():
00150                 [pub.publish(Empty()) for pub in self._disable_pub.values()]
00151                 self._enable_pub.publish(False)
00152                 self._tuck_rate.sleep()
00153 
00154     def _move_to(self, tuck, disabled):
00155         if any(disabled.values()):
00156             [pub.publish(Empty()) for pub in self._disable_pub.values()]
00157         while (any(self._arm_state['tuck'][limb] != goal
00158                    for limb, goal in tuck.viewitems())
00159                and not rospy.is_shutdown()):
00160             if self._rs.state().enabled == False:
00161                 self._enable_pub.publish(True)
00162             for limb in self._limbs:
00163                 if disabled[limb]:
00164                     self._disable_pub[limb].publish(Empty())
00165                 if limb in tuck:
00166                     self._arms[limb].set_joint_positions(dict(zip(
00167                                       self._arms[limb].joint_names(),
00168                                       self._joint_moves[tuck[limb]][limb])))
00169             self._check_arm_state()
00170             self._tuck_rate.sleep()
00171 
00172         if any(self._arm_state['collide'].values()):
00173             self._rs.disable()
00174         return
00175 
00176     def supervised_tuck(self):
00177         # Update our starting state to check if arms are tucked
00178         self._prepare_to_tuck()
00179         self._check_arm_state()
00180         # Tuck Arms
00181         if self._tuck == True:
00182             # If arms are already tucked, report this to user and exit.
00183             if all(self._arm_state['tuck'][limb] == 'tuck'
00184                    for limb in self._limbs):
00185                 rospy.loginfo("Tucking: Arms already in 'Tucked' position.")
00186                 self._done = True
00187                 return
00188             else:
00189                 rospy.loginfo("Tucking: One or more arms not Tucked.")
00190                 any_flipped = not all(self._arm_state['flipped'].values())
00191                 if any_flipped:
00192                     rospy.loginfo(
00193                         "Moving to neutral start position with collision %s.",
00194                         "on" if any_flipped else "off")
00195                 # Move to neutral pose before tucking arms to avoid damage
00196                 self._check_arm_state()
00197                 actions = dict()
00198                 disabled = {'left': True, 'right': True}
00199                 for limb in self._limbs:
00200                     if not self._arm_state['flipped'][limb]:
00201                         actions[limb] = 'untuck'
00202                         disabled[limb] = False
00203                 self._move_to(actions, disabled)
00204 
00205                 # Disable collision and Tuck Arms
00206                 rospy.loginfo("Tucking: Tucking with collision avoidance off.")
00207                 actions = {'left': 'tuck', 'right': 'tuck'}
00208                 disabled = {'left': True, 'right': True}
00209                 self._move_to(actions, disabled)
00210                 self._done = True
00211                 return
00212 
00213         # Untuck Arms
00214         else:
00215             # If arms are tucked disable collision and untuck arms
00216             if any(self._arm_state['flipped'].values()):
00217                 rospy.loginfo("Untucking: One or more arms Tucked;"
00218                               " Disabling Collision Avoidance and untucking.")
00219                 self._check_arm_state()
00220                 suppress = deepcopy(self._arm_state['flipped'])
00221                 actions = {'left': 'untuck', 'right': 'untuck'}
00222                 self._move_to(actions, suppress)
00223                 self._done = True
00224                 return
00225             # If arms already untucked, move to neutral location
00226             else:
00227                 rospy.loginfo("Untucking: Arms already Untucked;"
00228                               " Moving to neutral position.")
00229                 self._check_arm_state()
00230                 suppress = deepcopy(self._arm_state['flipped'])
00231                 actions = {'left': 'untuck', 'right': 'untuck'}
00232                 self._move_to(actions, suppress)
00233                 self._done = True
00234                 return
00235 
00236     def clean_shutdown(self):
00237         """Handles ROS shutdown (Ctrl-C) safely."""
00238         if not self._done:
00239             rospy.logwarn('Aborting: Shutting down safely...')
00240         if any(self._arm_state['collide'].values()):
00241             while self._rs.state().enabled != False:
00242                 [pub.publish(Empty()) for pub in self._disable_pub.values()]
00243                 self._enable_pub.publish(False)
00244                 self._tuck_rate.sleep()
00245 
00246 
00247 def main():
00248     parser = argparse.ArgumentParser()
00249     tuck_group = parser.add_mutually_exclusive_group(required=True)
00250     tuck_group.add_argument("-t", "--tuck", dest="tuck",
00251         action='store_true', default=False, help="tuck arms")
00252     tuck_group.add_argument("-u", "--untuck", dest="untuck",
00253         action='store_true', default=False, help="untuck arms")
00254     args = parser.parse_args(rospy.myargv()[1:])
00255     tuck = args.tuck
00256 
00257     rospy.loginfo("Initializing node... ")
00258     rospy.init_node("rsdk_tuck_arms")
00259     rospy.loginfo("%sucking arms" % ("T" if tuck else "Unt",))
00260     tucker = Tuck(tuck)
00261     rospy.on_shutdown(tucker.clean_shutdown)
00262     tucker.supervised_tuck()
00263     rospy.loginfo("Finished tuck")
00264 
00265 if __name__ == "__main__":
00266     main()


baxter_tools
Author(s): Rethink Robotics Inc.
autogenerated on Wed Aug 26 2015 10:50:53