AP_BattMonitor: add Maxell Battery support

This commit is contained in:
Tatsuya Yamaguchi 2017-02-09 09:28:57 +09:00 committed by Randy Mackay
parent d30350276c
commit 3e445fd4b8
5 changed files with 139 additions and 5 deletions

View File

@ -74,7 +74,7 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = {
// @Param: 2_MONITOR
// @DisplayName: Battery monitoring
// @Description: Controls enabling monitoring of the battery's voltage and current
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:SMBus,6:Bebop
// @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:Maxell
// @User: Standard
AP_GROUPINFO("2_MONITOR", 11, AP_BattMonitor, _monitoring[1], BattMonitor_TYPE_NONE),
@ -180,6 +180,10 @@ AP_BattMonitor::init()
hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_INTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR));
_num_instances++;
break;
case BattMonitor_TYPE_MAXELL:
state[instance].instance = instance;
drivers[instance] = new AP_BattMonitor_SMBus_Maxell(*this, instance, state[instance],
hal.i2c_mgr->get_device(AP_BATTMONITOR_SMBUS_BUS_EXTERNAL, AP_BATTMONITOR_SMBUS_I2C_ADDR));
_num_instances++;
break;
case BattMonitor_TYPE_BEBOP:
@ -224,8 +228,9 @@ bool AP_BattMonitor::has_current(uint8_t instance) const
// check for analog voltage and current monitor or smbus monitor
if (instance < _num_instances && drivers[instance] != nullptr) {
return (_monitoring[instance] == BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT ||
_monitoring[instance] == BattMonitor_TYPE_BEBOP);
_monitoring[instance] == BattMonitor_TYPE_SOLO ||
_monitoring[instance] == BattMonitor_TYPE_BEBOP ||
_monitoring[instance] == BattMonitor_TYPE_MAXELL);
}
// not monitoring current
@ -279,7 +284,7 @@ uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const
return 0;
}
}
/// exhausted - returns true if the voltage remains below the low_voltage for 10 seconds or remaining capacity falls below min_capacity_mah
bool AP_BattMonitor::exhausted(uint8_t instance, float low_voltage, float min_capacity_mah)
{
@ -332,4 +337,3 @@ bool AP_BattMonitor::overpower_detected(uint8_t instance) const
return false;
#endif
}

View File

@ -20,6 +20,7 @@ class AP_BattMonitor_Analog;
class AP_BattMonitor_SMBus;
class AP_BattMonitor_SMBus_Solo;
class AP_BattMonitor_SMBus_PX4;
class AP_BattMonitor_SMBus_Maxell;
class AP_BattMonitor
{
@ -28,6 +29,7 @@ class AP_BattMonitor
friend class AP_BattMonitor_SMBus;
friend class AP_BattMonitor_SMBus_Solo;
friend class AP_BattMonitor_SMBus_PX4;
friend class AP_BattMonitor_SMBus_Maxell;
public:
@ -39,8 +41,9 @@ public:
BattMonitor_TYPE_NONE = 0,
BattMonitor_TYPE_ANALOG_VOLTAGE_ONLY = 3,
BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT = 4,
BattMonitor_TYPE_BEBOP = 6
BattMonitor_TYPE_SOLO = 5,
BattMonitor_TYPE_BEBOP = 6,
BattMonitor_TYPE_MAXELL = 7
};
// The BattMonitor_State structure is filled in by the backend driver

View File

@ -27,3 +27,4 @@ public:
// include specific implementations
#include "AP_BattMonitor_SMBus_PX4.h"
#include "AP_BattMonitor_SMBus_Solo.h"
#include "AP_BattMonitor_SMBus_Maxell.h"

View File

@ -0,0 +1,96 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_SMBus_Maxell.h"
#include <utility>
extern const AP_HAL::HAL& hal;
#include <AP_HAL/AP_HAL.h>
#define BATTMONITOR_SMBUS_MAXELL_VOLTAGE 0x09 // voltage register
#define BATTMONITOR_SMBUS_MAXELL_CURRENT 0x0a // current register
/*
* Other potentially useful registers, listed here for future use
* #define BATTMONITOR_SMBUS_MAXELL_TEMP 0x08 // temperature register
* #define BATTMONITOR_SMBUS_MAXELL_CHARGE_STATUS 0x0d // relative state of charge
* #define BATTMONITOR_SMBUS_MAXELL_BATTERY_STATUS 0x16 // battery status register including alarms
* #define BATTMONITOR_SMBUS_MAXELL_BATTERY_CYCLE_COUNT 0x17 // cycle count
* #define BATTMONITOR_SMBUS_MAXELL_DESIGN_VOLTAGE 0x19 // design voltage register
* #define BATTMONITOR_SMBUS_MAXELL_SPECIFICATION_INFO 0x1a // specification info
* #define BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_NAME 0x1b // manufacturer name
* #define BATTMONITOR_SMBUS_MAXELL_SERIALNUM 0x1c // serial number register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE6 0x3a // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE5 0x3b // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE4 0x3c // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE3 0x3d // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE2 0x3e // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_CELL_VOLTAGE1 0x3f // cell voltage register
* #define BATTMONITOR_SMBUS_MAXELL_HEALTH_STATUS 0x4f // state of health
* #define BATTMONITOR_SMBUS_MAXELL_SAFETY_ALERT 0x50 // safety alert
* #define BATTMONITOR_SMBUS_MAXELL_SAFETY_STATUS 0x50 // safety status
* #define BATTMONITOR_SMBUS_MAXELL_PF_ALERT 0x52 // safety status
* #define BATTMONITOR_SMBUS_MAXELL_PF_STATUS 0x53 // safety status
*/
// Constructor
AP_BattMonitor_SMBus_Maxell::AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, uint8_t instance,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_BattMonitor_SMBus(mon, instance, mon_state)
, _dev(std::move(dev))
{
_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus_Maxell::timer, void));
}
/// Read the battery voltage and current. Should be called at 10hz
void AP_BattMonitor_SMBus_Maxell::read()
{
// nothing to do - all done in timer()
}
void AP_BattMonitor_SMBus_Maxell::timer()
{
uint16_t data;
uint32_t tnow = AP_HAL::micros();
// read voltage (V)
if (read_word(BATTMONITOR_SMBUS_MAXELL_VOLTAGE, data)) {
_state.voltage = (float)data / 1000.0f;
_state.last_time_micros = tnow;
_state.healthy = true;
}
// timeout after 5 seconds
if ((tnow - _state.last_time_micros) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) {
_state.healthy = false;
return;
}
// read current (A)
if (read_word(BATTMONITOR_SMBUS_MAXELL_CURRENT, data)) {
_state.current_amps = -(float)((int16_t)data) / 1000.0f;
_state.last_time_micros = tnow;
}
}
// read word from register
// returns true if read was successful, false if failed
bool AP_BattMonitor_SMBus_Maxell::read_word(uint8_t reg, uint16_t& data) const
{
uint8_t buff[2]; // buffer to hold results
// read three bytes and place in last three bytes of buffer
if (!_dev->read_registers(reg, buff, sizeof(buff))) {
return false;
}
// convert buffer to word
data = (uint16_t)buff[1]<<8 | (uint16_t)buff[0];
// return success
return true;
}

View File

@ -0,0 +1,30 @@
#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Math/AP_Math.h>
#include "AP_BattMonitor_SMBus.h"
#include <AP_HAL/I2CDevice.h>
class AP_BattMonitor_SMBus_Maxell : public AP_BattMonitor_SMBus
{
public:
// Constructor
AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon, uint8_t instance,
AP_BattMonitor::BattMonitor_State &mon_state,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
// read does nothing, all done in timer
void read() override;
private:
void timer(void);
// read word from register
// returns true if read was successful, false if failed
bool read_word(uint8_t reg, uint16_t& data) const;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
};