diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp index 337cd9f9ee..fa999abfaf 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp @@ -16,7 +16,12 @@ uint8_t smbus_cell_ids[] = { 0x3f, // cell 1 0x37, // cell 9 0x36, // cell 10 0x35, // cell 11 - 0x34}; // cell 12 + 0x34, // cell 12 +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + 0x33, // cell 13 + 0x32 // cell 14 +#endif +}; #define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes. #define SMBUS_CELL_COUNT_CHECK_TIMEOUT 15 // check cell count for up to 15 seconds diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h index 003229f746..df5f5fa54e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h @@ -2,7 +2,11 @@ #include "AP_BattMonitor_SMBus.h" +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define BATTMONITOR_SMBUS_NUM_CELLS_MAX 14 +#else #define BATTMONITOR_SMBUS_NUM_CELLS_MAX 12 +#endif class AP_BattMonitor_SMBus_Generic : public AP_BattMonitor_SMBus {