Skip to content

Commit

Permalink
autotest: fix testing and simulated register scaling
Browse files Browse the repository at this point in the history
* make test actually test something

* fix scaling to match datasheet values
  • Loading branch information
tpwrules committed Dec 2, 2024
1 parent adfc415 commit da4fee5
Showing 1 changed file with 14 additions and 11 deletions.
25 changes: 14 additions & 11 deletions Tools/autotest/ardusub.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,

Expand All @@ -975,21 +975,24 @@ 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:
# expected to take under 1 simulated second, but don't hang if
# e.g. the driver gets stuck
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):
Expand Down

0 comments on commit da4fee5

Please sign in to comment.