2020-10-20 19:41:31 -03:00
|
|
|
#include "SIM_BattMonitor_SMBus.h"
|
|
|
|
|
|
|
|
#include <AP_Stats/AP_Stats.h>
|
|
|
|
|
|
|
|
SITL::SIM_BattMonitor_SMBus::SIM_BattMonitor_SMBus() :
|
2021-01-04 22:59:19 -04:00
|
|
|
SMBusDevice()
|
2020-10-20 19:41:31 -03:00
|
|
|
{
|
2021-10-11 02:04:21 -03:00
|
|
|
add_register("Temperature", SMBusBattDevReg::TEMP, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Voltage", SMBusBattDevReg::VOLTAGE, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Current", SMBusBattDevReg::CURRENT, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Remaining Capacity", SMBusBattDevReg::REMAINING_CAPACITY, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Full Charge Capacity", SMBusBattDevReg::FULL_CHARGE_CAPACITY, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Cycle_Count", SMBusBattDevReg::CYCLE_COUNT, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Specification Info", SMBusBattDevReg::SPECIFICATION_INFO, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Serial", SMBusBattDevReg::SERIAL, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_block("Manufacture Name", SMBusBattDevReg::MANUFACTURE_NAME, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_block("Device Name", SMBusBattDevReg::DEVICE_NAME, SITL::I2CRegisters::RegMode::RDONLY);
|
|
|
|
add_register("Manufacture Data", SMBusBattDevReg::MANUFACTURE_DATA, SITL::I2CRegisters::RegMode::RDONLY);
|
2020-10-20 19:41:31 -03:00
|
|
|
|
2022-01-12 08:03:25 -04:00
|
|
|
set_register(SMBusBattDevReg::TEMP, (int16_t)((C_TO_KELVIN(15))*10));
|
2020-10-20 19:41:31 -03:00
|
|
|
// see update for voltage
|
|
|
|
// see update for current
|
|
|
|
// TODO: remaining capacity
|
|
|
|
// TODO: full capacity
|
|
|
|
set_register(SMBusBattDevReg::CYCLE_COUNT, (uint16_t(39U)));
|
|
|
|
|
|
|
|
// Set SPECIFICATION_INFO
|
|
|
|
union {
|
|
|
|
struct {
|
|
|
|
uint8_t revision : 4;
|
|
|
|
uint8_t version: 4;
|
|
|
|
uint8_t vscale: 4;
|
|
|
|
uint8_t ipscale: 4;
|
|
|
|
} fields;
|
|
|
|
uint16_t word;
|
|
|
|
} specinfo;
|
|
|
|
|
|
|
|
specinfo.fields.revision = 0b0001; // version 1
|
|
|
|
// specinfo.fields.version = 0b0011; // 1.1 with PEC; TODO!
|
|
|
|
specinfo.fields.version = 0b0001; // 1.0
|
|
|
|
specinfo.fields.vscale = 0b0000; // unknown...
|
|
|
|
specinfo.fields.ipscale = 0b0000; // unknown...
|
|
|
|
set_register(SMBusBattDevReg::SPECIFICATION_INFO, specinfo.word);
|
|
|
|
|
|
|
|
set_register(SMBusBattDevReg::SERIAL, (uint16_t)12345);
|
|
|
|
|
|
|
|
const char *manufacturer_name = "ArduPilot";
|
2021-01-04 22:59:19 -04:00
|
|
|
set_block(SMBusBattDevReg::MANUFACTURE_NAME, manufacturer_name);
|
|
|
|
|
|
|
|
const char *device_name = "SITLBatMon_V0.99";
|
|
|
|
set_block(SMBusBattDevReg::DEVICE_NAME, device_name);
|
|
|
|
|
2020-10-20 19:41:31 -03:00
|
|
|
// TODO: manufacturer data
|
|
|
|
}
|
|
|
|
|
|
|
|
void SITL::SIM_BattMonitor_SMBus::update(const class Aircraft &aircraft)
|
|
|
|
{
|
|
|
|
const uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - last_update_ms > 100) {
|
|
|
|
const float millivolts = AP::sitl()->state.battery_voltage * 1000.0f;
|
|
|
|
set_register(SMBusBattDevReg::VOLTAGE, uint16_t(millivolts));
|
|
|
|
// FIXME: is this REALLY what the hardware will do?
|
|
|
|
const int16_t current = constrain_int32(AP::sitl()->state.battery_current*-1000, -32768, 32767);
|
|
|
|
set_register(SMBusBattDevReg::CURRENT, current);
|
|
|
|
last_update_ms = now;
|
|
|
|
}
|
|
|
|
}
|