mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_BattMonitor: Solo add support for temperature and cells
Also fixs a buffer overflow when reading the ManufacturerData
This commit is contained in:
parent
043b93d643
commit
8f24d211ce
@ -10,16 +10,19 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#define BATTMONITOR_SMBUS_SOLO_TEMP 0x08 // temperature register
|
||||
#define BATTMONITOR_SMBUS_SOLO_VOLTAGE 0x09 // voltage register
|
||||
#define BATTMONITOR_SMBUS_SOLO_REMAINING_CAPACITY 0x0f // predicted remaining battery capacity in milliamps
|
||||
#define BATTMONITOR_SMBUS_SOLO_FULL_CHARGE_CAPACITY 0x10 // full capacity register
|
||||
#define BATTMONITOR_SMBUS_SOLO_MANUFACTURE_DATA 0x23 /// manufacturer data
|
||||
#define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register
|
||||
#define BATTMONITOR_SMBUS_SOLO_CURRENT 0x2a // current register
|
||||
#define BATTMONITOR_SMBUS_SOLO_BUTTON_DEBOUNCE 3 // button held down for 3 intervals will cause a power off event
|
||||
|
||||
#define BATTMONITOR_SMBUS_SOLO_NUM_CELLS 4
|
||||
|
||||
/*
|
||||
* Other potentially useful registers, listed here for future use
|
||||
* #define BATTMONITOR_SMBUS_SOLO_TEMP 0x08 // temperature register
|
||||
* #define BATTMONITOR_SMBUS_SOLO_BATTERY_STATUS 0x16 // battery status register including alarms
|
||||
* #define BATTMONITOR_SMBUS_SOLO_DESIGN_CAPACITY 0x18 // design capacity register
|
||||
* #define BATTMONITOR_SMBUS_SOLO_DESIGN_VOLTAGE 0x19 // design voltage register
|
||||
@ -28,7 +31,6 @@ extern const AP_HAL::HAL& hal;
|
||||
* #define BATTMONITOR_SMBUS_SOLO_DEVICE_NAME 0x21 // device name
|
||||
* #define BATTMONITOR_SMBUS_SOLO_DEVICE_CHEMISTRY 0x22 // device chemistry
|
||||
* #define BATTMONITOR_SMBUS_SOLO_MANUFACTURE_INFO 0x25 // manufacturer info including cell voltage
|
||||
* #define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register
|
||||
*/
|
||||
|
||||
// Constructor
|
||||
@ -50,7 +52,7 @@ void AP_BattMonitor_SMBus_Solo::read()
|
||||
void AP_BattMonitor_SMBus_Solo::timer()
|
||||
{
|
||||
uint16_t data;
|
||||
uint8_t buff[4];
|
||||
uint8_t buff[8];
|
||||
uint32_t tnow = AP_HAL::micros();
|
||||
|
||||
// read voltage
|
||||
@ -108,6 +110,19 @@ void AP_BattMonitor_SMBus_Solo::timer()
|
||||
}
|
||||
AP_Notify::flags.powering_off = _state.is_powering_off;
|
||||
}
|
||||
|
||||
// read temperature
|
||||
if (read_word(BATTMONITOR_SMBUS_SOLO_TEMP, data)) {
|
||||
_state.temperature_time = AP_HAL::millis();
|
||||
_state.temperature = ((float)(data - 2731)) * 0.1f;
|
||||
}
|
||||
|
||||
// read cell voltages
|
||||
if (read_block(BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE, buff, 8, false)) {
|
||||
for (uint8_t i = 0; i < BATTMONITOR_SMBUS_SOLO_NUM_CELLS; i++) {
|
||||
_state.cell_voltages.cells[i] = buff[(i * 2) + 1] << 8 | buff[i * 2];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// read word from register
|
||||
|
Loading…
Reference in New Issue
Block a user