00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 import roslib; roslib.load_manifest('sr_ronex_drivers')
00021 import rospy
00022 import sys, getopt
00023
00024 from threading import Lock
00025 from sr_ronex_msgs.msg import BoolArray
00026 from std_msgs.msg import UInt16MultiArray
00027
00028 PRODUCT_CODE = "0x05300424"
00029 DIGITAL_IO_WAIT = 0.5
00030 ANALOG_IO_WAIT = 0.1
00031 PWM_O_WAIT = 3.0
00032 ANALOG_RATIO_UPPER = 1.4
00033 ANALOG_RATIO_LOWER = 1.0
00034 PERIOD_ALPHA = 0.01
00035 MAX_PWM_PERIOD = 0.008
00036 MIN_PWM_PERIOD = 0.005
00037
00038 class IoTest(object):
00039 """
00040 A class used to test the Shadow Robot ethercat board HW.
00041 For the PRODUCT_CODE = "0x05300424"
00042 4 digital inputs/outputs/PWM outputs
00043 4 analog inputs
00044 2 analog outputs
00045
00046 The digital outputs will be tested by turning on and off LEDs attached to them.
00047 The digital inputs will read back the value we set for the outputs.
00048 The PWM outputs will be set to their lower frequency, and the digital inputs used to check the on-off period
00049 The analog output 0 will be wired to analog inputs 0 and 2, output 1 to inputs 1 and 3
00050
00051 Keep in mind that the test is intended to be run with the LEDs attached to the digital I/Os and the correct wiring of the analog I and O
00052 """
00053
00054
00055
00056
00057
00058
00059
00060 def __init__(self, device_SN):
00061 rospy.loginfo("Testing device. Product code: " + PRODUCT_CODE + " SN: " + device_SN)
00062 self.success = True
00063 self.PWM_testing = False
00064 self.device_SN = device_SN
00065 self.a_state_lock = Lock()
00066 self.d_state_lock = Lock()
00067 self.analog_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_analog_outputs_command", UInt16MultiArray, latch=True)
00068 self.digital_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_digital_outputs_command", BoolArray, latch=True)
00069 self.PWM_command_publisher = rospy.Publisher("/device_" + PRODUCT_CODE + "_" + device_SN + "_PWM_outputs_command", UInt16MultiArray, latch=True)
00070 self.analog_state_subscriber_ = rospy.Subscriber("/device_" + PRODUCT_CODE + "_" + device_SN + "_analog_inputs_state", UInt16MultiArray, self.analog_state_callback)
00071 self.digital_state_subscriber_ = rospy.Subscriber("/device_" + PRODUCT_CODE + "_" + device_SN + "_digital_inputs_state", BoolArray, self.digital_state_callback)
00072
00073 self.last_analog_state = None
00074 self.last_digital_state = None
00075 self.last_period_start_time = [0.0, 0.0, 0.0, 0.0]
00076 self.average_period = [0.0, 0.0, 0.0, 0.0]
00077
00078
00079 command_msg = UInt16MultiArray(None, [0, 0, 0, 0, 0, 0, 0, 0])
00080 self.PWM_command_publisher.publish(command_msg)
00081 rospy.sleep(0.2)
00082
00083
00084
00085 def analog_state_callback(self, msg):
00086 with self.a_state_lock:
00087 self.last_analog_state = msg
00088
00089 def digital_state_callback(self, msg):
00090 with self.d_state_lock:
00091 if self.PWM_testing:
00092 for i, value in enumerate(self.last_digital_state.data):
00093
00094 if value and not msg.data[i]:
00095 if self.last_period_start_time[i] != 0.0:
00096 self.average_period[i] = (1- PERIOD_ALPHA) * self.average_period[i] + PERIOD_ALPHA * (rospy.get_time() - self.last_period_start_time[i])
00097 self.last_period_start_time[i] = rospy.get_time()
00098 self.last_digital_state = msg
00099
00100
00101 def check_digital_inputs(self, output_values):
00102 rospy.sleep(0.1)
00103 with self.d_state_lock:
00104 if self.last_digital_state != None:
00105 for i, value in enumerate(output_values):
00106 if i & 1:
00107 if self.last_digital_state.data[i/2] != value:
00108 rospy.logerr("Wrong value in digital input " + str(i/2))
00109 self.success = False
00110 else:
00111 rospy.logerr("No digital input data recived from: " + self.device_SN)
00112 self.success = False
00113
00114 def test_digital_io_case(self, output_values):
00115 command_msg = BoolArray(output_values)
00116 self.digital_command_publisher.publish(command_msg)
00117 self.check_digital_inputs(output_values)
00118 rospy.sleep(DIGITAL_IO_WAIT)
00119
00120 def test_digital_ios(self):
00121 rospy.loginfo("Testing digital I/O")
00122 self.test_digital_io_case([False, False, False, False, False, False, False, False])
00123 self.test_digital_io_case([False, True, False, False, False, False, False, False])
00124 self.test_digital_io_case([False, False, False, True, False, False, False, False])
00125 self.test_digital_io_case([False, False, False, False, False, True, False, False])
00126 self.test_digital_io_case([False, False, False, False, False, False, False, True])
00127 self.test_digital_io_case([False, True, False, True, False, True, False, True])
00128 self.test_digital_io_case([False, False, False, False, False, False, False, False])
00129 rospy.loginfo("Digital I/O test ended")
00130
00131 def check_analog_inputs(self, output_values):
00132 rospy.sleep(0.1)
00133 with self.a_state_lock:
00134 if self.last_analog_state != None:
00135 for i, value in enumerate(output_values):
00136 index = i
00137 if (float(value) / float(self.last_analog_state.data[index])) > ANALOG_RATIO_UPPER or \
00138 (float(value) / float(self.last_analog_state.data[index])) < ANALOG_RATIO_LOWER:
00139 rospy.logerr("Wrong value in analog input " + str(index) + " set: " + str(value) + " measured: " + str(self.last_analog_state.data[index]) + " ratio: " + str(float(value) / float(self.last_analog_state.data[index])))
00140 self.success = False
00141 index = i + 2
00142 if (float(value) / float(self.last_analog_state.data[index])) > ANALOG_RATIO_UPPER or \
00143 (float(value) / float(self.last_analog_state.data[index])) < ANALOG_RATIO_LOWER:
00144 rospy.logerr("Wrong value in analog input " + str(index) + " set: " + str(value) + " measured: " + str(self.last_analog_state.data[index]) + " ratio: " + str(float(value) / float(self.last_analog_state.data[index])))
00145 self.success = False
00146 else:
00147 rospy.logerr("No analog input data recived from: " + self.device_SN)
00148 self.success = False
00149
00150
00151 def test_analog_io_case(self, output_values):
00152 command_msg = UInt16MultiArray(None, output_values)
00153 self.analog_command_publisher.publish(command_msg)
00154 self.check_analog_inputs(output_values)
00155 rospy.sleep(ANALOG_IO_WAIT)
00156
00157 def test_analog_ios(self):
00158 rospy.loginfo("Testing analog I/O")
00159 rospy.sleep(0.1)
00160 self.test_analog_io_case([0x200, 0x200])
00161 self.test_analog_io_case([0x200, 0xFF00])
00162 self.test_analog_io_case([0xFF00, 0x200])
00163 self.test_analog_io_case([0x200, 0x200])
00164 self.test_analog_io_case([0x300, 0x300])
00165 self.test_analog_io_case([0x1000, 0x1000])
00166 self.test_analog_io_case([0x5000, 0x5000])
00167 self.test_analog_io_case([0x8000, 0x8000])
00168 self.test_analog_io_case([0xA000, 0xA000])
00169 self.test_analog_io_case([0xC000, 0xC000])
00170 self.test_analog_io_case([0xD000, 0xD000])
00171 self.test_analog_io_case([0xE000, 0xE000])
00172 self.test_analog_io_case([0xF000, 0xF000])
00173 self.test_analog_io_case([0xFF00, 0xFF00])
00174 rospy.loginfo("Analog I/O test ended")
00175
00176 def test_PWM_o_case(self, output_values):
00177 command_msg = UInt16MultiArray(None, output_values)
00178 self.PWM_testing = True
00179 self.PWM_command_publisher.publish(command_msg)
00180
00181 rospy.sleep(PWM_O_WAIT)
00182 for i, value in enumerate(self.average_period):
00183 if value > MAX_PWM_PERIOD or value < MIN_PWM_PERIOD:
00184 rospy.logerr("Wrong period in PWM output " + str(i) + " measured period: " + str(value))
00185 self.success = False
00186 self.PWM_testing = False
00187
00188 def test_PWM_outputs(self):
00189 rospy.loginfo("Testing PWM outputs")
00190 self.test_PWM_o_case([0xFFFE, 0x8000, 0xFFFE, 0x8000, 0xFFFE, 0x8000, 0xFFFE, 0x8000])
00191 rospy.loginfo("PWM outputs test ended")
00192
00193
00194 def ramp(self):
00195 for i in range(0, 65535, 0x100):
00196 command_msg = UInt16MultiArray(None, [i, i])
00197 self.analog_command_publisher.publish(command_msg)
00198 rospy.sleep(0.03)
00199
00200
00201 def run_test(self):
00202 self.test_digital_ios()
00203 self.test_analog_ios()
00204 self.test_PWM_outputs()
00205
00206 if self.success:
00207 rospy.loginfo("NO ERRORS DETECTED. Product code: " + PRODUCT_CODE + " SN: " + self.device_SN)
00208 else:
00209 rospy.logerr("TEST FAILED. ERRORS DETECTED!!!!!!!!!!!!!!!!!!!!!!!!!! Product code: " + PRODUCT_CODE + " SN: " + self.device_SN)
00210
00211 def main(argv):
00212 try:
00213 opts, args = getopt.getopt(argv,"h")
00214 except getopt.GetoptError:
00215 print 'io_test.py <SN_device_1> ... <SN_device_N>'
00216 sys.exit(2)
00217 for opt, arg in opts:
00218 if opt == '-h':
00219 print 'io_test.py <SN_device_1> ... <SN_device_N>'
00220 sys.exit()
00221
00222 if len(args) == 0:
00223 print 'io_test.py <SN_device_1> ... <SN_device_N>'
00224 sys.exit(2)
00225
00226
00227 rospy.init_node('IO_test', anonymous=True)
00228 rospy.sleep(0.5)
00229
00230 for arg in args:
00231 io_test = IoTest(arg)
00232 io_test.run_test()
00233
00234 rospy.loginfo("I/O test ended")
00235
00236
00237
00238
00239
00240 if __name__ == '__main__':
00241 main(sys.argv[1:])
00242
00243