Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add support for triple-channel INA3221 i2c voltage-and-current sensor #15091

Merged
merged 7 commits into from
Dec 2, 2024
49 changes: 49 additions & 0 deletions Tools/autotest/ardusub.py
Original file line number Diff line number Diff line change
Expand Up @@ -947,6 +947,54 @@ def FuseMag(self):
self.wait_ready_to_arm()
self.assert_mag_fusion_selection(MagFuseSel.FUSE_MAG)

def INA3221(self):
'''test INA3221 driver'''
self.set_parameters({
"BATT2_MONITOR": 30,
"BATT3_MONITOR": 30,
"BATT4_MONITOR": 30,
})
self.reboot_sitl()
self.set_parameters({
"BATT2_I2C_ADDR": 0x42, # address defined in libraries/SITL/SIM_I2C.cpp
"BATT2_I2C_BUS": 1,
"BATT2_CHANNEL": 1,

"BATT3_I2C_ADDR": 0x42,
"BATT3_I2C_BUS": 1,
"BATT3_CHANNEL": 2,

"BATT4_I2C_ADDR": 0x42,
"BATT4_I2C_BUS": 1,
"BATT4_CHANNEL": 3,
})
self.reboot_sitl()

seen_1 = False
seen_3 = False
tstart = self.get_sim_time()
while not (seen_1 and seen_3):
m = self.assert_receive_message('BATTERY_STATUS')
if self.get_sim_time() - tstart > 10:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

10s results in a timeout when running at standard speed on a mac M1. With --speedup 2 the test completes. Not sure what the policy is for autotest (do we assume that in CI they'll be run with a speedup?). Increasing to 15 passes.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is strange to hear, I chose 10 seconds as a "couldn't possibly fail" value. There might be an inherent test timeout too which would remove the need to check, but I'm not 100% sure? Also get_sim_time should be scaled with speedup.

How are you running the test? Using Tools/autotest/autotest.py build.Sub test.Sub.INA3221 --no-clean and a print statement the total elapsed "time" is well under 1 second on my x86 machine and passes every time. I tested using --speedup=1, --speedup=2, and whatever the autotest script default is.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Disregard - I was using a --debug build and that explains the timeout.

# 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, {
# 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, {
# 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):
'''return list of all tests'''
ret = super(AutoTestSub, self).tests()
Expand Down Expand Up @@ -978,6 +1026,7 @@ def tests(self):
self.SetGlobalOrigin,
self.BackupOrigin,
self.FuseMag,
self.INA3221,
])

return ret
8 changes: 7 additions & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -4364,7 +4364,13 @@ def message_has_field_values_field_values_equal(self, fieldname, value, got, eps

def message_has_field_values(self, m, fieldvalues, verbose=True, epsilon=None):
for (fieldname, value) in fieldvalues.items():
got = getattr(m, fieldname)
if "[" in fieldname: # fieldname == "arrayname[index]"
assert fieldname[-1] == "]", fieldname
arrayname, index = fieldname.split("[", 1)
index = int(index[:-1])
got = getattr(m, arrayname)[index]
else:
got = getattr(m, fieldname)

value_string = value
got_string = got
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ def config_option(self):
Feature('Battery', 'BATTERY_FUELLEVEL_ANALOG', 'AP_BATTERY_FUELLEVEL_ANALOG_ENABLED', 'Enable Analog Fuel level battry monitor', 0, None), # noqa: E501
Feature('Battery', 'BATTERY_SMBUS', 'AP_BATTERY_SMBUS_ENABLED', 'Enable SMBUS battery monitor', 0, None),
Feature('Battery', 'BATTERY_INA2XX', 'AP_BATTERY_INA2XX_ENABLED', 'Enable INA2XX battery monitor', 0, None),
Feature('Battery', 'BATTERY_INA3221', 'AP_BATTERY_INA3221_ENABLED', 'Enable INA3221 battery monitor', 0, None),
Feature('Battery', 'BATTERY_SYNTHETIC_CURRENT', 'AP_BATTERY_SYNTHETIC_CURRENT_ENABLED', 'Enable Synthetic Current monitor', 0, None), # noqa: E501
Feature('Battery', 'BATTERY_ESC_TELEM_OUT', 'AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'Enable Ability to put battery monitor data into ESC telem stream', 0, None), # noqa: E501
Feature('Battery', 'BATTERY_SUM', 'AP_BATTERY_SUM_ENABLED', 'Enable Synthetic sum-of-other-batteries backend', 0, None), # noqa: E501
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include "AP_BattMonitor_EFI.h"
#include "AP_BattMonitor_INA2xx.h"
#include "AP_BattMonitor_INA239.h"
#include "AP_BattMonitor_INA3221.h"
#include "AP_BattMonitor_LTC2946.h"
#include "AP_BattMonitor_Torqeedo.h"
#include "AP_BattMonitor_FuelLevel_Analog.h"
Expand Down Expand Up @@ -604,6 +605,11 @@ AP_BattMonitor::init()
drivers[instance] = NEW_NOTHROW AP_BattMonitor_Scripting(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTERY_SCRIPTING_ENABLED
#if AP_BATTERY_INA3221_ENABLED
case Type::INA3221:
drivers[instance] = NEW_NOTHROW AP_BattMonitor_INA3221(*this, state[instance], _params[instance]);
break;
#endif // AP_BATTERY_INA3221_ENABLED
case Type::NONE:
default:
break;
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_BattMonitor/AP_BattMonitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ class AP_BattMonitor
friend class AP_BattMonitor_INA239;
friend class AP_BattMonitor_LTC2946;
friend class AP_BattMonitor_AD7091R5;
friend class AP_BattMonitor_INA3221;

friend class AP_BattMonitor_Torqeedo;
friend class AP_BattMonitor_FuelLevel_Analog;
Expand Down Expand Up @@ -116,6 +117,7 @@ class AP_BattMonitor
EFI = 27,
AD7091R5 = 28,
Scripting = 29,
INA3221 = 30,
};

FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t);
Expand Down
Loading
Loading