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
00037 import roslib
00038 roslib.load_manifest('qualification')
00039 import rospy, sys, time
00040 import subprocess
00041 from optparse import OptionParser
00042 from std_msgs.msg import Bool, Float64
00043
00044 class SendMessageOnSubscribe(rospy.SubscribeListener):
00045 def __init__(self, msg):
00046 self.msg = msg
00047 print "Waiting for subscriber..."
00048
00049 def peer_subscribe(self, topic_name, topic_publish, peer_publish):
00050 peer_publish(self.msg)
00051 time.sleep(0.1)
00052
00053
00054 def set_controller(controller, command):
00055 pub = rospy.Publisher(controller + '/command', Float64,
00056 SendMessageOnSubscribe(Float64(command)))
00057
00058 def hold_arm(side, pan_angle):
00059
00060 set_controller("%s_wrist_roll_position_controller" % side, float(0.0))
00061 set_controller("%s_wrist_flex_position_controller" % side, float(1.0))
00062 set_controller("%s_forearm_roll_position_controller" % side, float(0.0))
00063 set_controller("%s_elbow_flex_position_controller" % side, float(-0.5))
00064 set_controller("%s_upper_arm_roll_position_controller" % side, float(0.0))
00065 set_controller("%s_shoulder_lift_position_controller" % side, float(0.0))
00066 set_controller("%s_shoulder_pan_position_controller" % side, float(pan_angle))
00067
00068
00069 def main():
00070 parser = OptionParser()
00071 parser.add_option('--wait-for', action="store", dest="wait_for_topic", default=None)
00072
00073 options, args = parser.parse_args(rospy.myargv())
00074
00075 rospy.init_node('arm_test_holder')
00076 pub_held = rospy.Publisher('arms_held', Bool, latch=True)
00077
00078
00079 try:
00080 if options.wait_for_topic:
00081 global result
00082 result = None
00083 def wait_for_topic_cb(msg):
00084 global result
00085 result = msg
00086
00087 rospy.Subscriber(options.wait_for_topic, Bool, wait_for_topic_cb)
00088 started_waiting = rospy.get_time()
00089
00090
00091 warned_about_not_hearing_anything = False
00092 while not result and not rospy.is_shutdown():
00093 time.sleep(0.01)
00094 if not warned_about_not_hearing_anything:
00095 if rospy.get_time() - started_waiting > 10.0:
00096 warned_about_not_hearing_anything = True
00097 rospy.logwarn("Full arm holder hasn't heard anything from its \"wait for\" topic (%s)" % \
00098 options.wait_for_topic)
00099 if result:
00100 while not result.data and not rospy.is_shutdown():
00101 time.sleep(0.01)
00102
00103 if not rospy.is_shutdown():
00104 rospy.loginfo('Raising torso')
00105 set_controller("torso_lift_position_controller", float(0.20))
00106 time.sleep(3)
00107
00108 if not rospy.is_shutdown():
00109 rospy.loginfo('Holding arms')
00110
00111 hold_arm('r', -1.2)
00112 hold_arm('l', 1.2)
00113 time.sleep(1.5)
00114
00115 if not rospy.is_shutdown():
00116 pub_held.publish(True)
00117
00118 rospy.spin()
00119 except KeyboardInterrupt:
00120 pass
00121 except:
00122 import traceback
00123 traceback.print_exc()
00124
00125 if __name__ == '__main__':
00126 main()