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 import roslib
00037 roslib.load_manifest('qualification')
00038
00039 from pr2_self_test_msgs.srv import *
00040
00041 import rospy
00042
00043 NAME = 'ethernet'
00044
00045 import os
00046 import sys
00047 from StringIO import StringIO
00048
00049 def ethernet_test():
00050 rospy.init_node(NAME)
00051
00052 name = rospy.myargv()[1]
00053 ip = rospy.myargv()[2]
00054
00055 res = os.popen('ping -f -q -w 1 -s 32768 %s' % (ip)).readlines()
00056
00057 r = TestResultRequest()
00058 r.plots = []
00059
00060 if (len(res) > 1):
00061 tran = float(res[3].split()[0])
00062 recv = float(res[3].split()[3])
00063
00064 r.html_result = r.html_result + '<p>Flood Ping Transmitted: %f</p>'%(tran)
00065 r.html_result = r.html_result + '<p>Flood Ping Received: %f</p>'%(recv)
00066
00067 if ((tran - recv) <= 2):
00068 res = os.popen('netperf -H %s -t UDP_STREAM -l 1' % (ip)).readlines()
00069
00070 speed = float(res[6].split()[3])
00071 speed_str = ''
00072
00073 r.result = TestResultRequest.RESULT_PASS
00074
00075 if (speed > 750):
00076 speed_str = 'Gigabit'
00077 elif (speed > 100):
00078 speed_str = 'Gigabit (slow)'
00079 r.result = TestResultRequest.RESULT_FAIL
00080 elif (speed > 75):
00081 speed_str = '100 Megabit'
00082 r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
00083 elif (speed > 10):
00084 speed_str = '100 Megabit (slow)'
00085 r.result = TestResultRequest.RESULT_FAIL
00086 else:
00087 speed_str = '< 10 Megabit'
00088 r.result = TestResultRequest.RESULT_FAIL
00089
00090 r.text_summary = speed_str
00091 r.html_result = r.html_result + '<p>Speed: %f (%s).</p>'%(speed, speed_str)
00092 else:
00093 r.text_summary = 'Too many packets lost.'
00094 r.html_result = r.html_result + '<p>Too many packets lost.</p>'
00095 else:
00096 r.text_summary = 'Running ping failed.'
00097 r.html_result = r.html_result + '<p>Running ping failed!</p>'
00098
00099
00100 rospy.wait_for_service('test_result')
00101 result_service = rospy.ServiceProxy('test_result', TestResult)
00102 result_service.call(r)
00103
00104 if __name__ == "__main__":
00105 ethernet_test()