mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_BattMonitor: add cells 13 and 14 for SITL only
Allows for testing higher-cell-count scenarios
This commit is contained in:
parent
bf10b454d1
commit
278dc4a09b
@ -16,7 +16,12 @@ uint8_t smbus_cell_ids[] = { 0x3f, // cell 1
|
|||||||
0x37, // cell 9
|
0x37, // cell 9
|
||||||
0x36, // cell 10
|
0x36, // cell 10
|
||||||
0x35, // cell 11
|
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_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
|
#define SMBUS_CELL_COUNT_CHECK_TIMEOUT 15 // check cell count for up to 15 seconds
|
||||||
|
@ -2,7 +2,11 @@
|
|||||||
|
|
||||||
#include "AP_BattMonitor_SMBus.h"
|
#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
|
#define BATTMONITOR_SMBUS_NUM_CELLS_MAX 12
|
||||||
|
#endif
|
||||||
|
|
||||||
class AP_BattMonitor_SMBus_Generic : public AP_BattMonitor_SMBus
|
class AP_BattMonitor_SMBus_Generic : public AP_BattMonitor_SMBus
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user