@ -5,12 +5,6 @@
@@ -5,12 +5,6 @@
# include "AP_BattMonitor_SMBus_Maxell.h"
# include <utility>
extern const AP_HAL : : HAL & hal ;
# include <AP_HAL/AP_HAL.h>
# define BATTMONITOR_SMBUS_MAXELL_TEMP 0x08 // temperature register
# define BATTMONITOR_SMBUS_MAXELL_VOLTAGE 0x09 // voltage register
# define BATTMONITOR_SMBUS_MAXELL_CURRENT 0x0a // current register
# define BATTMONITOR_SMBUS_MAXELL_SPECIFICATION_INFO 0x1a // specification info
@ -45,8 +39,7 @@ uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
@@ -45,8 +39,7 @@ uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
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 ) )
: AP_BattMonitor_SMBus ( mon , instance , mon_state , std : : move ( dev ) )
{
_dev - > register_periodic_callback ( 100000 , FUNCTOR_BIND_MEMBER ( & AP_BattMonitor_SMBus_Maxell : : timer , void ) ) ;
}
@ -102,34 +95,6 @@ void AP_BattMonitor_SMBus_Maxell::timer()
@@ -102,34 +95,6 @@ void AP_BattMonitor_SMBus_Maxell::timer()
}
}
// 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
{
// buffer to hold results (1 extra byte returned holding PEC)
const uint8_t read_size = 2 + ( _pec_supported ? 1 : 0 ) ;
uint8_t buff [ read_size ] ; // 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 ;
}
// check PEC
if ( _pec_supported ) {
const uint8_t pec = get_PEC ( AP_BATTMONITOR_SMBUS_I2C_ADDR , reg , true , buff , 2 ) ;
if ( pec ! = buff [ 2 ] ) {
return false ;
}
}
// convert buffer to word
data = ( uint16_t ) buff [ 1 ] < < 8 | ( uint16_t ) buff [ 0 ] ;
// return success
return true ;
}
// read_block - returns number of characters read if successful, zero if unsuccessful
uint8_t AP_BattMonitor_SMBus_Maxell : : read_block ( uint8_t reg , uint8_t * data , bool append_zero ) const
{