Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 """
00036 usage: tuck_arms.py [-l ACTION] [-r ACTION]
00037
00038 Options:
00039 -l or --left Action for left arm
00040 -r or --right Action for right arm
00041
00042 Actions:
00043 t or tuck
00044 u or untuck
00045
00046 NB: If action unspecified for an arm, defaults to tuck
00047
00048 """
00049
00050
00051 import getopt
00052
00053 import rospy
00054
00055 import actionlib
00056
00057 from pr2_common_action_msgs.msg import TuckArmsAction, TuckArmsGoal
00058
00059 def main():
00060 action_name = 'tuck_arms'
00061
00062
00063 myargs = rospy.myargv()[1:]
00064 if len(myargs):
00065 goal = TuckArmsGoal()
00066 goal.tuck_left = True
00067 goal.tuck_right = True
00068 opts, args = getopt.getopt(myargs, 'hql:r:', ['quit','left','right'])
00069 for arm, action in opts:
00070 if arm in ('-l', '--left'):
00071 if action in ('tuck', 't'):
00072 goal.tuck_left = True
00073 elif action in ('untuck', 'u'):
00074 goal.tuck_left = False
00075 else:
00076 rospy.logerr('Invalid action for right arm: %s'%action)
00077 rospy.signal_shutdown("ERROR")
00078
00079 if arm in ('-r', '--right'):
00080 if action in ('tuck', 't'):
00081 goal.tuck_right = True
00082 elif action in ('untuck', 'u'):
00083 goal.tuck_right = False
00084 else:
00085 rospy.logerr('Invalid action for left arm: %s'%action)
00086 rospy.signal_shutdown("ERROR")
00087
00088 if arm in ('--help', '-h'):
00089 print __doc__ % vars()
00090
00091 tuck_arm_client = actionlib.SimpleActionClient(action_name, TuckArmsAction)
00092 rospy.logdebug('Waiting for action server to start')
00093 tuck_arm_client.wait_for_server(rospy.Duration(10.0))
00094 rospy.logdebug('Sending goal to action server')
00095 tuck_arm_client.send_goal_and_wait(goal, rospy.Duration(30.0), rospy.Duration(5.0))
00096
00097 if __name__ == "__main__":
00098 rospy.init_node('tuck_amrs_test')
00099 main()