2017-02-08 20:28:57 -04:00
# include <AP_HAL/AP_HAL.h>
# include <AP_Common/AP_Common.h>
# include <AP_Math/AP_Math.h>
# include "AP_BattMonitor.h"
2020-06-02 04:21:10 -03:00
# include "AP_BattMonitor_SMBus_Generic.h"
2017-02-08 20:28:57 -04:00
# include <utility>
2020-06-02 22:59:54 -03:00
uint8_t smbus_cell_ids [ ] = { 0x3f , // cell 1
0x3e , // cell 2
0x3d , // cell 3
0x3c , // cell 4
0x3b , // cell 5
0x3a , // cell 6
0x39 , // cell 7
0x38 , // cell 8
0x37 , // cell 9
0x36 , // cell 10
0x35 , // cell 11
2021-06-09 00:30:51 -03:00
0x34 , // cell 12
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
0x33 , // cell 13
0x32 // cell 14
# endif
} ;
2017-04-08 01:21:43 -03:00
2017-03-29 07:49:10 -03:00
# define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes.
2020-06-23 01:53:15 -03:00
# define SMBUS_CELL_COUNT_CHECK_TIMEOUT 15 // check cell count for up to 15 seconds
2017-02-08 20:28:57 -04:00
/*
* Other potentially useful registers , listed here for future use
* # 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
2017-02-19 04:50:06 -04:00
* # define BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_DATE 0x1b // manufacturer date
2017-02-08 20:28:57 -04:00
* # define BATTMONITOR_SMBUS_MAXELL_SERIALNUM 0x1c // serial number register
* # define BATTMONITOR_SMBUS_MAXELL_HEALTH_STATUS 0x4f // state of health
* # define BATTMONITOR_SMBUS_MAXELL_SAFETY_ALERT 0x50 // safety alert
2018-11-08 18:43:59 -04:00
* # define BATTMONITOR_SMBUS_MAXELL_SAFETY_STATUS 0x51 // safety status
2017-02-08 20:28:57 -04:00
* # define BATTMONITOR_SMBUS_MAXELL_PF_ALERT 0x52 // safety status
* # define BATTMONITOR_SMBUS_MAXELL_PF_STATUS 0x53 // safety status
*/
// Constructor
2020-06-02 04:21:10 -03:00
AP_BattMonitor_SMBus_Generic : : AP_BattMonitor_SMBus_Generic ( AP_BattMonitor & mon ,
2017-02-08 20:28:57 -04:00
AP_BattMonitor : : BattMonitor_State & mon_state ,
2021-06-18 18:16:06 -03:00
AP_BattMonitor_Params & params )
: AP_BattMonitor_SMBus ( mon , mon_state , params , AP_BATTMONITOR_SMBUS_BUS_EXTERNAL )
2017-10-26 00:58:56 -03:00
{ }
2017-02-08 20:28:57 -04:00
2020-06-02 04:21:10 -03:00
void AP_BattMonitor_SMBus_Generic : : timer ( )
2017-02-08 20:28:57 -04:00
{
2017-03-29 07:49:10 -03:00
// check if PEC is supported
if ( ! check_pec_support ( ) ) {
return ;
2017-02-19 04:50:06 -04:00
}
2020-06-23 01:53:15 -03:00
uint16_t data ;
2017-02-08 20:28:57 -04:00
uint32_t tnow = AP_HAL : : micros ( ) ;
// read voltage (V)
2017-12-29 05:39:57 -04:00
if ( read_word ( BATTMONITOR_SMBUS_VOLTAGE , data ) ) {
2017-02-08 20:28:57 -04:00
_state . voltage = ( float ) data / 1000.0f ;
_state . last_time_micros = tnow ;
_state . healthy = true ;
}
2020-06-23 01:53:15 -03:00
// assert that BATTMONITOR_SMBUS_NUM_CELLS_MAX must be no more than smbus_cell_ids
static_assert ( BATTMONITOR_SMBUS_NUM_CELLS_MAX < = ARRAY_SIZE ( smbus_cell_ids ) , " BATTMONITOR_SMBUS_NUM_CELLS_MAX must be no more than smbus_cell_ids " ) ;
2020-06-02 22:59:54 -03:00
// check cell count
if ( ! _cell_count_fixed ) {
if ( _state . healthy ) {
// when battery first becomes healthy, start check of cell count
if ( _cell_count_check_start_us = = 0 ) {
_cell_count_check_start_us = tnow ;
}
2020-06-23 01:53:15 -03:00
if ( tnow - _cell_count_check_start_us > ( SMBUS_CELL_COUNT_CHECK_TIMEOUT * 1e6 ) ) {
2020-06-02 22:59:54 -03:00
// give up checking cell count after 15sec of continuous healthy battery reads
_cell_count_fixed = true ;
}
} else {
// if battery becomes unhealthy restart cell count check
_cell_count_check_start_us = 0 ;
}
}
2021-06-09 00:26:55 -03:00
// we loop over something limted by
// BATTMONITOR_SMBUS_NUM_CELLS_MAX but assign into something
// limited by AP_BATT_MONITOR_CELLS_MAX - so make sure we won't
// over-write:
static_assert ( BATTMONITOR_SMBUS_NUM_CELLS_MAX < = ARRAY_SIZE ( _state . cell_voltages . cells ) , " BATTMONITOR_SMBUS_NUM_CELLS_MAX must be <= number of cells in state voltages " ) ;
2017-04-08 05:23:45 -03:00
// read cell voltages
2020-06-02 22:59:54 -03:00
for ( uint8_t i = 0 ; i < ( _cell_count_fixed ? _cell_count : BATTMONITOR_SMBUS_NUM_CELLS_MAX ) ; i + + ) {
if ( read_word ( smbus_cell_ids [ i ] , data ) & & ( data > 0 ) & & ( data < UINT16_MAX ) ) {
2017-06-11 05:59:02 -03:00
_has_cell_voltages = true ;
2017-04-08 01:21:43 -03:00
_state . cell_voltages . cells [ i ] = data ;
2020-06-02 22:59:54 -03:00
_last_cell_update_us [ i ] = tnow ;
if ( ! _cell_count_fixed ) {
_cell_count = MAX ( _cell_count , i + 1 ) ;
}
} else if ( ( tnow - _last_cell_update_us [ i ] ) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS ) {
2017-04-08 01:21:43 -03:00
_state . cell_voltages . cells [ i ] = UINT16_MAX ;
}
}
2017-02-08 20:28:57 -04:00
// timeout after 5 seconds
if ( ( tnow - _state . last_time_micros ) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS ) {
_state . healthy = false ;
return ;
}
// read current (A)
2017-12-29 05:39:57 -04:00
if ( read_word ( BATTMONITOR_SMBUS_CURRENT , data ) ) {
2017-02-08 20:28:57 -04:00
_state . current_amps = - ( float ) ( ( int16_t ) data ) / 1000.0f ;
_state . last_time_micros = tnow ;
}
2017-04-08 05:23:45 -03:00
2017-04-24 03:49:51 -03:00
read_full_charge_capacity ( ) ;
2018-12-10 19:30:47 -04:00
// FIXME: Perform current integration if the remaining capacity can't be requested
2017-05-16 01:34:08 -03:00
read_remaining_capacity ( ) ;
2017-04-19 17:49:38 -03:00
read_temp ( ) ;
2017-04-24 03:16:49 -03:00
read_serial_number ( ) ;
2019-12-10 20:55:20 -04:00
read_cycle_count ( ) ;
2017-02-08 20:28:57 -04:00
}
2017-02-19 04:50:06 -04:00
// read_block - returns number of characters read if successful, zero if unsuccessful
2020-06-02 04:21:10 -03:00
uint8_t AP_BattMonitor_SMBus_Generic : : read_block ( uint8_t reg , uint8_t * data , bool append_zero ) const
2017-02-19 04:50:06 -04:00
{
// get length
uint8_t bufflen ;
// read byte (first byte indicates the number of bytes in the block)
if ( ! _dev - > read_registers ( reg , & bufflen , 1 ) ) {
return 0 ;
}
// sanity check length returned by smbus
2017-03-29 07:49:10 -03:00
if ( bufflen = = 0 | | bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER ) {
2017-02-19 04:50:06 -04:00
return 0 ;
}
// buffer to hold results (2 extra byte returned holding length and PEC)
2017-03-29 07:41:43 -03:00
const uint8_t read_size = bufflen + 1 + ( _pec_supported ? 1 : 0 ) ;
2017-02-19 04:50:06 -04:00
uint8_t buff [ read_size ] ;
// read bytes
if ( ! _dev - > read_registers ( reg , buff , read_size ) ) {
return 0 ;
}
// check PEC
2017-03-29 07:49:10 -03:00
if ( _pec_supported ) {
2017-02-19 04:50:06 -04:00
uint8_t pec = get_PEC ( AP_BATTMONITOR_SMBUS_I2C_ADDR , reg , true , buff , bufflen + 1 ) ;
if ( pec ! = buff [ bufflen + 1 ] ) {
return 0 ;
}
}
// copy data (excluding PEC)
memcpy ( data , & buff [ 1 ] , bufflen ) ;
// optionally add zero to end
if ( append_zero ) {
data [ bufflen ] = ' \0 ' ;
}
// return success
return bufflen ;
}
2017-03-29 07:49:10 -03:00
// check if PEC supported with the version value in SpecificationInfo() function
// returns true once PEC is confirmed as working or not working
2020-06-02 04:21:10 -03:00
bool AP_BattMonitor_SMBus_Generic : : check_pec_support ( )
2017-02-19 04:50:06 -04:00
{
2017-03-29 07:49:10 -03:00
// exit immediately if we have already confirmed pec support
if ( _pec_confirmed ) {
return true ;
}
2017-02-19 04:50:06 -04:00
// specification info
2017-03-29 07:49:10 -03:00
uint16_t data ;
2017-12-29 05:39:57 -04:00
if ( ! read_word ( BATTMONITOR_SMBUS_SPECIFICATION_INFO , data ) ) {
2017-02-20 12:42:33 -04:00
return false ;
}
2017-03-29 07:49:10 -03:00
// extract version
uint8_t version = ( data & 0xF0 ) > > 4 ;
2017-02-20 12:42:33 -04:00
2017-03-29 07:49:10 -03:00
// version less than 0011b (i.e. 3) do not support PEC
if ( version < 3 ) {
_pec_supported = false ;
_pec_confirmed = true ;
2017-02-20 12:42:33 -04:00
return true ;
}
2017-03-29 07:49:10 -03:00
// check manufacturer name
uint8_t buff [ SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1 ] ;
2017-12-29 05:39:57 -04:00
if ( read_block ( BATTMONITOR_SMBUS_MANUFACTURE_NAME , buff , true ) ) {
2017-03-29 07:49:10 -03:00
// Hitachi maxell batteries do not support PEC
2017-02-20 12:42:33 -04:00
if ( strcmp ( ( char * ) buff , " Hitachi maxell " ) = = 0 ) {
2017-03-29 07:49:10 -03:00
_pec_supported = false ;
_pec_confirmed = true ;
2017-02-20 12:42:33 -04:00
return true ;
2017-02-19 04:50:06 -04:00
}
}
2017-03-29 07:49:10 -03:00
// assume all other batteries support PEC
_pec_supported = true ;
_pec_confirmed = true ;
return true ;
2017-02-20 12:42:33 -04:00
}
2017-02-19 04:50:06 -04:00