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