Browse Source

AP_BattMonitor: set default I2C bus for Solo and Maxell drivers

zr-v5.1
Randy Mackay 5 years ago committed by Andrew Tridgell
parent
commit
0288b3d43c
  1. 2
      libraries/AP_BattMonitor/AP_BattMonitor.cpp

2
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -114,11 +114,13 @@ AP_BattMonitor::init() @@ -114,11 +114,13 @@ AP_BattMonitor::init()
break;
#if HAL_BATTMON_SMBUS_ENABLE
case AP_BattMonitor_Params::BattMonitor_TYPE_SOLO:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_INTERNAL);
drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20));
break;
case AP_BattMonitor_Params::BattMonitor_TYPE_MAXELL:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_EXTERNAL);
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20));

Loading…
Cancel
Save