diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index a0eb71b5dac58d..89440e1ff4908d 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -956,7 +956,7 @@ def INA3221(self): }) self.reboot_sitl() self.set_parameters({ - "BATT2_I2C_ADDR": 0x42, + "BATT2_I2C_ADDR": 0x42, # address defined in libraries/SITL/SIM_I2C.cpp "BATT2_I2C_BUS": 1, "BATT2_CHANNEL": 1, @@ -975,21 +975,22 @@ def INA3221(self): tstart = self.get_sim_time() while not (seen_1 and seen_3): m = self.assert_receive_message('BATTERY_STATUS') - print(self.dump_message_verbose(m)) - if self.get_sim_time() - tstart > 1: - break - continue + if self.get_sim_time() - tstart > 10: + raise NotAchievedException("INA3221 status timeout") if m.id == 1: self.assert_message_field_values(m, { - "current_battery": 7.28 * 100, - }) - # "voltages[0]": 12 * 1000, + # values close to chip limits + "voltages[0]": int(25 * 1000), # millivolts + "current_battery": int(160 * 100), # centi-amps + }, epsilon=10) # allow rounding seen_1 = True + # id 2 is the first simulated battery current/voltage if m.id == 3: self.assert_message_field_values(m, { - "current_battery": 2.24 * 100, - }) - # "voltages[0]": 3.14159 * 1000, + # values different from above to test channel switching + "voltages[0]": int(3.14159 * 1000), # millivolts + "current_battery": int(2.71828 * 100), # centi-amps + }, epsilon=10) # allow rounding seen_3 = True def tests(self):