Browse Source

AP_BattMonitor: add SMBus address param and create SMBus subtree

gps-1.3.1
Josh Henderson 4 years ago committed by Andrew Tridgell
parent
commit
e37efa45de
  1. 144
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  2. 4
      libraries/AP_BattMonitor/AP_BattMonitor.h
  3. 7
      libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp
  4. 1
      libraries/AP_BattMonitor/AP_BattMonitor_Params.h
  5. 36
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp
  6. 9
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h
  7. 5
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp
  8. 3
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h
  9. 6
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.cpp
  10. 3
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.h
  11. 5
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp
  12. 1
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h
  13. 7
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp
  14. 3
      libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h

144
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -69,9 +69,51 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { @@ -69,9 +69,51 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Path: AP_BattMonitor_Params.cpp
AP_SUBGROUPINFO(_params[8], "9_", 31, AP_BattMonitor, AP_BattMonitor_Params),
#if HAL_BATTMON_SMBUS_ENABLE
// @Group: _
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[0], "_", 32, AP_BattMonitor, backend_smbus_var_info[0]),
// @Group: 2_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[1], "2_", 33, AP_BattMonitor, backend_smbus_var_info[1]),
// @Group: 3_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[2], "3_", 34, AP_BattMonitor, backend_smbus_var_info[2]),
// @Group: 4_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[3], "4_", 35, AP_BattMonitor, backend_smbus_var_info[3]),
// @Group: 5_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[4], "5_", 36, AP_BattMonitor, backend_smbus_var_info[4]),
// @Group: 6_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[5], "6_", 37, AP_BattMonitor, backend_smbus_var_info[5]),
// @Group: 7_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[6], "7_", 38, AP_BattMonitor, backend_smbus_var_info[6]),
// @Group: 8_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[7], "8_", 39, AP_BattMonitor, backend_smbus_var_info[7]),
// @Group: 9_
// @Path: AP_BattMonitor_SMBus.cpp
AP_SUBGROUPVARPTR(drivers[8], "9_", 40, AP_BattMonitor, backend_smbus_var_info[8]),
#endif // HAL_BATTMON_SMBUS_ENABLE
AP_GROUPEND
};
#if HAL_BATTMON_SMBUS_ENABLE
const AP_Param::GroupInfo *AP_BattMonitor::backend_smbus_var_info[AP_BATT_MONITOR_MAX_INSTANCES];
#endif
// Default constructor.
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
@ -121,45 +163,25 @@ AP_BattMonitor::init() @@ -121,45 +163,25 @@ AP_BattMonitor::init()
break;
#if HAL_BATTMON_SMBUS_ENABLE
case 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));
drivers[instance] = new AP_BattMonitor_SMBus_Solo(*this, state[instance], _params[instance]);
break;
case Type::SMBus_Generic:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_EXTERNAL);
drivers[instance] = new AP_BattMonitor_SMBus_Generic(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20));
drivers[instance] = new AP_BattMonitor_SMBus_Generic(*this, state[instance], _params[instance]);
break;
case Type::SUI3:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_INTERNAL),
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20), 3);
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 3);
break;
case Type::SUI6:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_INTERNAL),
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20), 6);
drivers[instance] = new AP_BattMonitor_SMBus_SUI(*this, state[instance], _params[instance], 6);
break;
case 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));
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, state[instance], _params[instance]);
break;
case Type::Rotoye:
drivers[instance] = new AP_BattMonitor_SMBus_Rotoye(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20));
drivers[instance] = new AP_BattMonitor_SMBus_Rotoye(*this, state[instance], _params[instance]);
break;
case Type::NeoDesign:
_params[instance]._i2c_bus.set_default(AP_BATTMONITOR_SMBUS_BUS_INTERNAL),
drivers[instance] = new AP_BattMonitor_SMBus_NeoDesign(*this, state[instance], _params[instance],
hal.i2c_mgr->get_device(_params[instance]._i2c_bus, AP_BATTMONITOR_SMBUS_I2C_ADDR,
100000, true, 20));
drivers[instance] = new AP_BattMonitor_SMBus_NeoDesign(*this, state[instance], _params[instance]);
break;
#endif // HAL_BATTMON_SMBUS_ENABLE
case Type::BEBOP:
@ -188,7 +210,6 @@ AP_BattMonitor::init() @@ -188,7 +210,6 @@ AP_BattMonitor::init()
drivers[instance] = new AP_BattMonitor_FuelLevel_PWM(*this, state[instance], _params[instance]);
break;
#endif // HAL_BATTMON_FUEL_ENABLE
#if GENERATOR_ENABLED
case Type::GENERATOR_ELEC:
drivers[instance] = new AP_BattMonitor_Generator_Elec(*this, state[instance], _params[instance]);
@ -207,6 +228,20 @@ AP_BattMonitor::init() @@ -207,6 +228,20 @@ AP_BattMonitor::init()
break;
}
#if HAL_BATTMON_SMBUS_ENABLE
// if the backend has some local parameters then make those available in the tree
if (drivers[instance] && state[instance].var_info) {
Type type = get_type(instance);
if ((type == Type::MAXELL) || (type == Type::NeoDesign) || (type == Type::Rotoye) || (type == Type::SMBus_Generic) ||
(type == Type::SOLO) || (type == Type::SUI3) || (type == Type::SUI6)) {
backend_smbus_var_info[instance] = state[instance].var_info;
AP_Param::load_object_from_eeprom(drivers[instance], backend_smbus_var_info[instance]);
}
// param count could have changed
AP_Param::invalidate_count();
}
#endif
// call init function for each backend
if (drivers[instance] != nullptr) {
drivers[instance]->init();
@ -215,10 +250,63 @@ AP_BattMonitor::init() @@ -215,10 +250,63 @@ AP_BattMonitor::init()
// there will be a gap, but as we always check for drivers[instances] being nullptr
// this is safe
_num_instances = instance + 1;
// Convert the old analog & Bus parameters to the new dynamic parameter groups
convert_dynamic_param_groups(instance);
}
}
}
void AP_BattMonitor::convert_dynamic_param_groups(uint8_t instance)
{
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {
return;
}
char param_prefix[6] {};
char param_name[17] {};
info.new_name = param_name;
const uint8_t param_instance = instance + 1;
// first battmonitor does not have '1' in the param name
if(param_instance == 1) {
hal.util->snprintf(param_prefix, sizeof(param_prefix), "BATT");
} else {
hal.util->snprintf(param_prefix, sizeof(param_prefix), "BATT%X", param_instance);
}
param_prefix[sizeof(param_prefix)-1] = '\0';
hal.util->snprintf(param_name, sizeof(param_name), "%s_%s", param_prefix, "MONITOR");
param_name[sizeof(param_name)-1] = '\0';
// Find the index of the BATTn_MONITOR which is not moving to index the moving parameters off from
AP_Param::ParamToken token = AP_Param::ParamToken {};
ap_var_type type;
AP_Param* param = AP_Param::find_by_name(param_name, &type, &token);
const uint8_t battmonitor_index = 1;
if( param == nullptr) {
// BATTn_MONITOR not found
return;
}
const struct convert_table {
uint32_t old_group_element;
ap_var_type type;
const char* new_name;
} conversion_table[] = {
{ 20, AP_PARAM_INT8, "I2C_BUS" },
};
for (const auto & elem : conversion_table) {
info.old_group_element = token.group_element + ((elem.old_group_element - battmonitor_index) * 64);;
info.type = elem.type;
hal.util->snprintf(param_name, sizeof(param_name), "%s_%s", param_prefix, elem.new_name);
AP_Param::convert_old_parameter(&info, 1.0f, 0);
}
}
void AP_BattMonitor::convert_params(void) {
if (_params[0]._type.configured_in_storage()) {
// _params[0]._type will always be configured in storage after conversion is done the first time

4
libraries/AP_BattMonitor/AP_BattMonitor.h

@ -128,8 +128,11 @@ public: @@ -128,8 +128,11 @@ public:
bool healthy; // battery monitor is communicating correctly
bool is_powering_off; // true when power button commands power off
bool powerOffNotified; // only send powering off notification once
const struct AP_Param::GroupInfo *var_info;
};
static const struct AP_Param::GroupInfo *backend_smbus_var_info[AP_BATT_MONITOR_MAX_INSTANCES];
// Return the number of battery monitor instances
uint8_t num_instances(void) const { return _num_instances; }
@ -237,6 +240,7 @@ private: @@ -237,6 +240,7 @@ private:
uint8_t _num_instances; /// number of monitors
void convert_params(void);
void convert_dynamic_param_groups(uint8_t instance);
/// returns the failsafe state of the battery
Failsafe check_failsafe(const uint8_t instance);

7
libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp

@ -164,12 +164,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { @@ -164,12 +164,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
// @User: Advanced
AP_GROUPINFO("ARM_MAH", 19, AP_BattMonitor_Params, _arming_minimum_capacity, 0),
// @Param: BUS
// @DisplayName: Battery monitor I2C bus number
// @Description: Battery monitor I2C bus number
// @Range: 0 3
// @User: Standard
AP_GROUPINFO("BUS", 20, AP_BattMonitor_Params, _i2c_bus, 0),
// 20 was BUS
// @Param: OPTIONS
// @DisplayName: Battery monitor options

1
libraries/AP_BattMonitor/AP_BattMonitor_Params.h

@ -40,7 +40,6 @@ public: @@ -40,7 +40,6 @@ public:
AP_Int8 _volt_pin; /// board pin used to measure battery voltage
AP_Int8 _curr_pin; /// board pin used to measure battery current
AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered
AP_Int8 _i2c_bus; /// I2C bus number
AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event
AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe
AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe

36
libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp

@ -2,19 +2,47 @@ @@ -2,19 +2,47 @@
#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_BattMonitor_SMBus::var_info[] = {
// @Param: I2C_BUS
// @DisplayName: Battery monitor I2C bus number
// @Description: Battery monitor I2C bus number
// @Range: 0 3
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("I2C_BUS", 1, AP_BattMonitor_SMBus, _bus, 0),
// @Param: I2C_ADDR
// @DisplayName: Battery monitor I2C address
// @Description: Battery monitor I2C address
// @Range: 0 127
// @User: Advanced
// @RebootRequired: True
AP_GROUPINFO("I2C_ADDR", 2, AP_BattMonitor_SMBus, _address, AP_BATTMONITOR_SMBUS_I2C_ADDR),
AP_GROUPEND
};
AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_BattMonitor_Backend(mon, mon_state, params),
_dev(std::move(dev))
uint8_t i2c_bus)
: AP_BattMonitor_Backend(mon, mon_state, params)
{
AP_Param::setup_object_defaults(this, var_info);
_state.var_info = var_info;
_bus.set_default(i2c_bus);
_params._serial_number = AP_BATT_SERIAL_NUMBER_DEFAULT;
_params._pack_capacity = 0;
}
void AP_BattMonitor_SMBus::init(void)
{
_dev = hal.i2c_mgr->get_device(_bus, _address, 100000, true, 20);
if (_dev) {
timer_handle = _dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus::timer, void));
}
@ -128,7 +156,7 @@ bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const @@ -128,7 +156,7 @@ bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const
// check PEC
if (_pec_supported) {
const uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, 2);
const uint8_t pec = get_PEC(_address, reg, true, buff, 2);
if (pec != buff[2]) {
return false;
}

9
libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h

@ -34,7 +34,7 @@ public: @@ -34,7 +34,7 @@ public:
AP_BattMonitor_SMBus(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
uint8_t i2c_bus);
// virtual destructor to reduce compiler warnings
virtual ~AP_BattMonitor_SMBus() {}
@ -54,6 +54,8 @@ public: @@ -54,6 +54,8 @@ public:
virtual void init(void) override;
static const struct AP_Param::GroupInfo var_info[];
protected:
void read(void) override;
@ -99,4 +101,9 @@ protected: @@ -99,4 +101,9 @@ protected:
virtual void timer(void) = 0; // timer function to read from the battery
AP_HAL::Device::PeriodicHandle timer_handle;
// Parameters
AP_Int8 _bus; // I2C bus number
AP_Int8 _address; // I2C address
};

5
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp

@ -44,9 +44,8 @@ uint8_t smbus_cell_ids[] = { 0x3f, // cell 1 @@ -44,9 +44,8 @@ uint8_t smbus_cell_ids[] = { 0x3f, // cell 1
// Constructor
AP_BattMonitor_SMBus_Generic::AP_BattMonitor_SMBus_Generic(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
AP_BattMonitor_Params &params)
: AP_BattMonitor_SMBus(mon, mon_state, params, AP_BATTMONITOR_SMBUS_BUS_EXTERNAL)
{}
void AP_BattMonitor_SMBus_Generic::timer()

3
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h

@ -15,8 +15,7 @@ public: @@ -15,8 +15,7 @@ public:
// Constructor
AP_BattMonitor_SMBus_Generic(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_BattMonitor_Params &params);
private:

6
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.cpp

@ -9,9 +9,8 @@ @@ -9,9 +9,8 @@
// Constructor
AP_BattMonitor_SMBus_NeoDesign::AP_BattMonitor_SMBus_NeoDesign(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
AP_BattMonitor_Params &params)
: AP_BattMonitor_SMBus(mon, mon_state, params, AP_BATTMONITOR_SMBUS_BUS_INTERNAL)
{
_pec_supported = true;
}
@ -76,4 +75,3 @@ void AP_BattMonitor_SMBus_NeoDesign::timer() @@ -76,4 +75,3 @@ void AP_BattMonitor_SMBus_NeoDesign::timer()
read_remaining_capacity();
read_temp();
}

3
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_NeoDesign.h

@ -7,8 +7,7 @@ class AP_BattMonitor_SMBus_NeoDesign : public AP_BattMonitor_SMBus @@ -7,8 +7,7 @@ class AP_BattMonitor_SMBus_NeoDesign : public AP_BattMonitor_SMBus
public:
AP_BattMonitor_SMBus_NeoDesign(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_BattMonitor_Params &params);
private:

5
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.cpp

@ -17,9 +17,8 @@ extern const AP_HAL::HAL& hal; @@ -17,9 +17,8 @@ extern const AP_HAL::HAL& hal;
AP_BattMonitor_SMBus_SUI::AP_BattMonitor_SMBus_SUI(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
uint8_t _cell_count)
: AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev)),
: AP_BattMonitor_SMBus(mon, mon_state, params, AP_BATTMONITOR_SMBUS_BUS_INTERNAL),
cell_count(_cell_count)
{
_pec_supported = false;
@ -84,7 +83,7 @@ bool AP_BattMonitor_SMBus_SUI::read_block(uint8_t reg, uint8_t* data, uint8_t le @@ -84,7 +83,7 @@ bool AP_BattMonitor_SMBus_SUI::read_block(uint8_t reg, uint8_t* data, uint8_t le
}
// check PEC
uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1);
if (pec != buff[bufflen+1]) {
return false;
}

1
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_SUI.h

@ -11,7 +11,6 @@ public: @@ -11,7 +11,6 @@ public:
AP_BattMonitor_SMBus_SUI(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
uint8_t cell_count
);

7
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp

@ -26,9 +26,8 @@ @@ -26,9 +26,8 @@
// Constructor
AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
AP_BattMonitor_Params &params)
: AP_BattMonitor_SMBus(mon, mon_state, params, AP_BATTMONITOR_SMBUS_BUS_INTERNAL)
{
_pec_supported = true;
}
@ -116,7 +115,7 @@ uint8_t AP_BattMonitor_SMBus_Solo::read_block(uint8_t reg, uint8_t* data, uint8_ @@ -116,7 +115,7 @@ uint8_t AP_BattMonitor_SMBus_Solo::read_block(uint8_t reg, uint8_t* data, uint8_
}
// check PEC
uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1);
if (pec != buff[bufflen+1]) {
return 0;
}

3
libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h

@ -9,8 +9,7 @@ public: @@ -9,8 +9,7 @@ public:
// Constructor
AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_BattMonitor_Params &params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_BattMonitor_Params &params);
private:

Loading…
Cancel
Save