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 pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest
00043 from pr2_power_board.srv import PowerBoardCommand
00044 import traceback
00045 import socket
00046
00047 BOARD_NAMESPACE = '/qualification/powerboard'
00048
00049 def main():
00050 parser = OptionParser()
00051 parser.add_option("--srv=", type="string", dest="service", action="store", default="prestartup_done")
00052 parser.add_option("--cmd=", type="string", dest="commands", action="append")
00053
00054 options, args = parser.parse_args()
00055
00056 rospy.init_node("power_cmd")
00057
00058 done_proxy = rospy.ServiceProxy(options.service, ScriptDone)
00059 done = ScriptDoneRequest()
00060 done.result = ScriptDoneRequest.RESULT_OK
00061 done.failure_msg = ''
00062
00063 try:
00064 rospy.wait_for_service('power_board/control', 5)
00065 except:
00066 rospy.logerr('Service wait timed out! %s' % traceback.format_exc())
00067
00068 done.result = ScriptDoneRequest.RESULT_ERROR
00069 done.failure_msg = 'Power bower service timed out! %s\n' % traceback.format_exc()
00070 try:
00071 rospy.wait_for_service(options.service, 5)
00072 done_proxy.call(done)
00073 finally:
00074 time.sleep(2)
00075
00076
00077
00078 serial = int(rospy.get_param('%s/serial' % BOARD_NAMESPACE, 0))
00079
00080 if serial == 0:
00081 done.result = ScriptDoneRequest.RESULT_ERROR
00082 done.failure_msg = 'No power board serial. Parameter \"%s/serial\" was unassigned.' % BOARD_NAMESPACE
00083 done_proxy.call(done)
00084 time.sleep(2)
00085
00086
00087 breakers = {}
00088 breakers[0] = rospy.get_param('%s/0' % BOARD_NAMESPACE, False)
00089 breakers[1] = rospy.get_param('%s/1' % BOARD_NAMESPACE, False)
00090 breakers[2] = rospy.get_param('%s/2' % BOARD_NAMESPACE, False)
00091
00092 rospy.loginfo('Board: %d, Breakers: %s, %s, %s' % (serial, breakers[0], breakers[1], breakers[2]))
00093
00094 brk_ok = False
00095 for brk in breakers:
00096 brk_ok = brk_ok or brk
00097 if not brk_ok:
00098 done.result = ScriptDoneRequest.RESULT_ERROR
00099 done.failure_msg = 'No breakers enabled.'
00100 done_proxy.call(done)
00101 time.sleep(2)
00102
00103 control_proxy = rospy.ServiceProxy('power_board/control', PowerBoardCommand)
00104
00105 is_first = True
00106 try:
00107 for power_cmd in options.commands:
00108
00109 if not is_first:
00110 time.sleep(2)
00111
00112 is_first = False
00113 for num in breakers.keys():
00114 if not breakers[num]:
00115 continue
00116
00117 resp = control_proxy(serial, num, power_cmd, 0)
00118 rospy.loginfo('CMD: %d %d %s. Received return code %d' %
00119 (serial, num, power_cmd, resp.retval))
00120 if resp.retval != 0:
00121 details = 'Commanded power board, return code %s.\n\n' % resp.retval
00122 if resp.retval == -1:
00123 details += 'Power board may not be connected. Check network connections.'
00124
00125 done.result = ScriptDoneRequest.RESULT_ERROR
00126 done.failure_msg = details
00127 break
00128
00129 except Exception, e:
00130 rospy.logerr('Caught exception!')
00131 rospy.logerr(traceback.format_exc())
00132 done.result = ScriptDoneRequest.RESULT_ERROR
00133 done.failure_msg = 'Caught exception.\n%s' % traceback.format_exc()
00134
00135 rospy.wait_for_service(options.service, 5)
00136 done_proxy.call(done)
00137 rospy.spin()
00138
00139
00140 if __name__ == '__main__':
00141 main()
00142
00143