mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_BattMonitor: zero-terminate strings in caller rather than read_block
It was noted that we did not increment the return value bufflen when adding zero. This is an ambiguity in the function declaration; if we are told to add a zero should the return value be like strnlen (does not include terminating null character) or read (includes all bytes used in return buffer). This PR makes it a non-issue by ensuring string null termination in the caller and removing the append_zero parameter.
This commit is contained in:
parent
6d7086a8ad
commit
2c0f52a8b7
@ -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;
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user