untuck_arms.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 # Modified by Kevin Watts for two arm use
00035 
00036 import roslib
00037 import signal
00038 roslib.load_manifest('pr2_tuckarm')
00039 
00040 import rospy
00041 import os
00042 
00043 from trajectory_msgs.msg import *
00044 from pr2_mechanism_msgs.msg import *
00045 from pr2_mechanism_msgs.srv import *
00046 
00047 import sys
00048 import time
00049 
00050 name_right = 'r_arm_controller'
00051 name_left = 'l_arm_controller'
00052 pub_right = rospy.Publisher('%s/command'%name_right, JointTrajectory, latch=True)
00053 pub_left = rospy.Publisher('%s/command'%name_left, JointTrajectory, latch=True)
00054 
00055 USAGE = 'tuckarm.py <arms> ; <arms> is \'(r)ight\', \'(l)eft\', or \'(b)oth\' arms'
00056 
00057 prev_handler = None
00058 resp =  SwitchControllerResponse()
00059 stop_list = []
00060 
00061 def shutdown(sig, stackframe):
00062   rospy.loginfo("Exiting tuckarm and bringing arm controllers back to their original state")
00063   resp = switch_controller([], stop_list, SwitchControllerRequest.STRICT)
00064   if not resp.ok:
00065     rospy.logerr("Could not stop arm controllers %s" %stop_list)            
00066   if prev_handler is not None:
00067     prev_handler(signal.SIGINT,None)
00068 
00069 
00070 def start_controller(name):
00071   started_trying = rospy.get_rostime()
00072   while not rospy.is_shutdown():
00073     try:
00074       resp = list_controller()
00075       i = resp.controllers.index(name)
00076 
00077       if resp.state[i] == 'stopped':
00078         resp = switch_controller([name], [], SwitchControllerRequest.STRICT)
00079         if not resp.ok:
00080           rospy.logerr("Could not start %s" % name)
00081           sys.exit(2)
00082         stop_list.append(name)
00083       break
00084     except ValueError:
00085       if started_trying and started_trying > rospy.get_rostime() + rospy.Duration(20.0):
00086         rospy.logerr("The controller %s is not loaded" % name)
00087         started_trying = None
00088       time.sleep(0.1)
00089 
00090 def go(side, positions):
00091   traj = JointTrajectory()
00092   traj.joint_names = ["%s_shoulder_pan_joint" % side, 
00093                       "%s_shoulder_lift_joint" % side,
00094                       "%s_upper_arm_roll_joint" % side,
00095                       "%s_elbow_flex_joint" % side, 
00096                       "%s_forearm_roll_joint" % side,
00097                       "%s_wrist_flex_joint" % side, 
00098                       "%s_wrist_roll_joint" % side]
00099   traj.points = []
00100 
00101   for p in positions:
00102     traj.points.append(JointTrajectoryPoint(positions = p[1:],
00103                                             velocities = [0.0] * (len(p) - 1),
00104                                             accelerations = [],
00105                                             time_from_start = rospy.Duration(p[0])))
00106 
00107   traj.header.stamp = rospy.get_rostime() + rospy.Duration(0.01)
00108 
00109   {'l': pub_left, 'r': pub_right}[side].publish(traj)
00110 
00111 
00112 
00113 if __name__ == '__main__':
00114   if len(sys.argv) < 2:
00115     print USAGE
00116     sys.exit(-1)
00117 
00118   side = sys.argv[1]
00119   
00120   rospy.init_node('tuck_arms', anonymous = True)
00121   rospy.loginfo("Waiting for controller manager to start")
00122   rospy.wait_for_service('pr2_controller_manager/switch_controller')
00123   list_controller = rospy.ServiceProxy('pr2_controller_manager/list_controllers', ListControllers)
00124   switch_controller = rospy.ServiceProxy('pr2_controller_manager/switch_controller', SwitchController)
00125 
00126 
00127   # Override rospy's signal handling.  We'll invoke rospy's handler after
00128   # we're done shutting down
00129   prev_handler = signal.getsignal(signal.SIGINT)
00130   signal.signal(signal.SIGINT, shutdown)
00131 
00132   # check if left and right controllers are loaded
00133   state_left = "undefined"
00134   state_right = "undefined"
00135   list_resp = list_controller()
00136   for (name, state) in zip(list_resp.controllers, list_resp.state):
00137     if name == name_left:
00138       state_left = state
00139     if name == name_right:
00140       state_right = state
00141 
00142   if side == 'l' or side == 'left': 
00143     rospy.loginfo("Tucking left arm")
00144     # tuck traj for left arm
00145     start_controller(name_left)
00146     positions = [[3.0, 0.4,0.0,0.0,-2.25,0.0,0.0,0.0],
00147                  [5.8, -0.05,1.31,1.38,-2.06,1.69,-2.02,2.44]]
00148     go('l', positions)
00149 
00150   elif side == 'r' or side == 'right':
00151     rospy.loginfo("Tucking right arm")
00152     # tuck traj for right arm
00153     start_controller(name_right)
00154     positions = [[3.0, -0.4,0.0,0.0,-1.57,0.0,0.0,0.0],
00155                  [5.0, 0.0,1.57,-1.57,-1.57,0.0,0.0,0.0]]    
00156 
00157     go('r', positions)
00158 
00159   elif side == 'b' or side == 'both':
00160     rospy.loginfo("Tucking both left and right arm")
00161     # Both arms
00162     start_controller(name_right)
00163     start_controller(name_left)
00164     
00165     positions_r = [[3.0, -0.4,0.0,0.0,-2.25,0.0,0.0,0.0],
00166                    [3.0, -0.4,0.0,0.0,-2.25,0.0,0.0,0.0]]
00167     positions_l = [[3.0, 0.4,0.0,0.0,-2.25,0.0,0.0,0.0],
00168                    [3.8, 0.4,0.0,0.0,-2.25,0.0,0.0,0.0],
00169                    [3.8, 0.4,0.0,0.0,-2.25,0.0,0.0,0.0]]
00170         
00171     go('l', positions_l)
00172     go('r', positions_r)
00173       
00174   else:
00175     print 'Unknown side! Must be l/left, r/right, or b/both!'
00176     print USAGE
00177     sys.exit(2)
00178   rospy.spin()


pr2_gazebo_wg
Author(s): John Hsu
autogenerated on Mon Jan 6 2014 12:05:36