handoff_node.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 import roslib; 
00004 roslib.load_manifest('hrl_pr2_kinematics_tutorials')
00005 roslib.load_manifest('rfid_people_following')
00006 roslib.load_manifest('hrl_lib')
00007 roslib.load_manifest('std_srvs')
00008 import rospy
00009 
00010 import hrl_pr2_kinematics_tutorials.hrl_pr2 as hrl_pr2
00011 import hrl_lib.transforms as tr
00012 import rfid_people_following.tactile_sensors as tsen
00013 from rfid_people_following.srv import FloatFloatFloatFloat_Int32 as arm_srv
00014 from rfid_people_following.srv import HandoffSrv
00015 
00016 import numpy as np, math
00017 import os
00018 import time
00019 
00020 class HandoffNode():
00021     def __init__( self ):
00022         rospy.init_node( 'handoff', anonymous = True )
00023         rospy.logout( 'handoff_node: Have run hrl_pr2_gains/change_gains.sh yet?' )
00024 
00025         self.robot = hrl_pr2.HRL_PR2()
00026         if not (os.environ.has_key('ROBOT') and os.environ['ROBOT'] == 'sim'):
00027             self.ts = tsen.TactileSensor()
00028         self.arm = 'right_arm'
00029 
00030         self.start_ja = [0.040304940763152608, 1.2398003444166741, -1.2204088251845415, -1.9324078526157087, -31.197472992401149, -1.7430222641585842, -1.5358378047038517]
00031         #self.target_ja = [0.35891507126604916, 0.13778228113494312, -0.01277662779292843, -1.4992538841561938, -28.605807802842136, -0.96590944225972863, -3.0950669743130161]
00032         self.target_ja = [0.0818, 0.377, -0.860, -2.144, -3.975, -1.479, 3.907]
00033 
00034         self._sh = rospy.Service( '/rfid_handoff/handoff' , HandoffSrv, self.handoff )
00035         self._si = rospy.Service( '/rfid_handoff/initialize' , HandoffSrv, self.initialize )
00036         self._sj = rospy.Service( '/rfid_handoff/handoff_pos' , arm_srv, self.handoff_pos )
00037         self._swave = rospy.Service( '/rfid_handoff/wave' , HandoffSrv, self.wave )
00038 
00039         # self.initialize()  # Prefer to do this manually... (rosservice call /rfid_handoff/initialize)
00040         rospy.logout( 'handoff_node: Waiting for service calls.' )
00041 
00042     def initialize( self, msg = None ):
00043         rospy.logout( 'handoff_node: Initializing. Hand me an object!' )
00044 
00045         # Put into handoff position, ready to accept object
00046         self.robot.set_jointangles( self.arm, self.target_ja, 3.0 )
00047         rospy.sleep( rospy.Duration( 3.0 ))
00048         self.robot.open_gripper( self.arm )
00049         rospy.sleep( rospy.Duration( 2.0 ))
00050 
00051         self.stow()
00052         return True
00053 
00054     def wave( self, msg = None ):
00055         wave_a = [0.0131, 0.325, -0.832, -1.762,-6.511, -0.191, 0.162]
00056         wave_b = [-0.180, 0.034, 0.108, -1.295, -6.224, -0.383, 0.119]
00057         self.robot.set_jointangles( self.arm, wave_a, 2.0 )
00058         rospy.sleep( rospy.Duration( 2.0 ))
00059         self.robot.set_jointangles( self.arm, wave_b, 1.0 )
00060         rospy.sleep( rospy.Duration( 1.0 ))
00061         self.robot.set_jointangles( self.arm, wave_a, 1.0 )
00062         rospy.sleep( rospy.Duration( 1.0 ))
00063         self.robot.set_jointangles( self.arm, wave_b, 1.0 )
00064         rospy.sleep( rospy.Duration( 1.0 ))
00065         self.robot.set_jointangles( self.arm, wave_a, 1.0 )
00066         rospy.sleep( rospy.Duration( 1.0 ))
00067         self.robot.set_jointangles( self.arm, self.start_ja, 3.0 )
00068         rospy.sleep( rospy.Duration( 3.0 ))
00069         return True
00070                 
00071 
00072 
00073     def stow( self ):
00074         # Grab object
00075         self.robot.close_gripper( self.arm )
00076         rospy.sleep( rospy.Duration( 2.0 ))
00077 
00078         # Stow
00079         self.robot.set_jointangles( self.arm, self.start_ja, 3.0 )
00080         rospy.sleep( rospy.Duration( 3.0 ))
00081 
00082 
00083     def open( self ):
00084         self.robot.open_gripper( self.arm )
00085         rospy.sleep( rospy.Duration( 2.0 ))
00086 
00087 
00088     def close( self ):
00089         self.robot.close_gripper( self.arm )
00090         rospy.sleep( rospy.Duration( 2.0 ))
00091 
00092 
00093     def handoff( self, msg = None ):
00094         # Put into handoff position.
00095         self.robot.set_jointangles( self.arm, self.target_ja, 3.0 )
00096         rospy.sleep( rospy.Duration( 3.0 ))
00097 
00098         # Tactile Sensor detector
00099         rospy.sleep( rospy.Duration( 0.5 ))
00100         self.ts.thresh_detect( 3000 )
00101 
00102         # Release object
00103         self.robot.open_gripper( self.arm )
00104         rospy.sleep( rospy.Duration( 2.0 ))
00105         
00106         # Stow
00107         self.robot.set_jointangles( self.arm, self.start_ja, 3.0 )
00108         rospy.sleep( rospy.Duration( 3.0 ))
00109         return True
00110 
00111     def handoff_pos( self, msg ):
00112         #pos = np.matrix([0.6977, -0.03622, 0.2015]).T
00113         #ang = tr.Rx(math.radians(0.))
00114         print msg
00115         pos = np.matrix([ msg.x, msg.y, msg.z ]).T
00116         ang = tr.Rx( msg.ang )
00117         
00118         q = [0, 0, 0, 0, 0, 0, 0]
00119         j = self.robot.IK('right_arm', pos, ang, self.target_ja)
00120         #j = self.robot.IK('right_arm', pos, ang, q)
00121         self.robot.set_jointangles( 'right_arm', j, 3.0 )
00122 
00123         # Tactile Sensor detector
00124         rospy.sleep( rospy.Duration( 0.5 ))
00125         self.ts.thresh_detect( 3000 )
00126 
00127         # Release object
00128         self.robot.open_gripper( self.arm )
00129         rospy.sleep( rospy.Duration( 2.0 ))
00130         
00131         # Stow
00132         self.robot.set_jointangles( self.arm, self.start_ja, 3.0 )
00133         rospy.sleep( rospy.Duration( 3.0 ))
00134 
00135         return True
00136         
00137 
00138 
00139 if __name__ == '__main__':
00140     hon = HandoffNode()
00141     #hon.handoff_pos()
00142     rospy.spin()
00143 
00144     #ho.handoff()
00145     


rfid_people_following
Author(s): Travis Deyle (Healthcare Robotics Lab, Georgia Tech)
autogenerated on Wed Nov 27 2013 11:38:30