diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp index ac23bc44c8..83d33c8984 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp @@ -130,7 +130,7 @@ void AP_BattMonitor_SMBus_Generic::timer() } // read_block - returns number of characters read if successful, zero if unsuccessful -uint8_t AP_BattMonitor_SMBus_Generic::read_block(uint8_t reg, uint8_t* data, bool append_zero) const +uint8_t AP_BattMonitor_SMBus_Generic::read_block(uint8_t reg, uint8_t* data) const { // get length uint8_t bufflen; @@ -164,11 +164,6 @@ uint8_t AP_BattMonitor_SMBus_Generic::read_block(uint8_t reg, uint8_t* data, boo // copy data (excluding PEC) memcpy(data, &buff[1], bufflen); - // optionally add zero to end - if (append_zero) { - data[bufflen] = '\0'; - } - // return success return bufflen; } @@ -199,8 +194,8 @@ bool AP_BattMonitor_SMBus_Generic::check_pec_support() } // check manufacturer name - uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1]; - if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_NAME, buff, true)) { + uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1] {}; + if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_NAME, buff)) { // Hitachi maxell batteries do not support PEC if (strcmp((char*)buff, "Hitachi maxell") == 0) { _pec_supported = false; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h index 34a5b139f6..fd19a830b2 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.h @@ -26,7 +26,7 @@ private: bool check_pec_support(); // read_block - returns number of characters read if successful, zero if unsuccessful - uint8_t read_block(uint8_t reg, uint8_t* data, bool append_zero) const; + uint8_t read_block(uint8_t reg, uint8_t* data) const; uint8_t _pec_confirmed; // count of the number of times PEC has been confirmed as working uint32_t _last_cell_update_us[BATTMONITOR_SMBUS_NUM_CELLS_MAX]; // system time of last successful read of cell voltage