mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: use correct unformatted system ID length
Avoids stuffing uninitialized data into the ID.
This commit is contained in:
parent
a3aa278589
commit
63ab7bec69
|
@ -243,15 +243,13 @@ bool Util::get_system_id(char buf[50])
|
||||||
|
|
||||||
bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len)
|
bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len)
|
||||||
{
|
{
|
||||||
len = MIN(12, len);
|
|
||||||
|
|
||||||
|
|
||||||
uint8_t base_mac_addr[6] = {0};
|
uint8_t base_mac_addr[6] = {0};
|
||||||
esp_err_t ret = esp_efuse_mac_get_custom(base_mac_addr);
|
esp_err_t ret = esp_efuse_mac_get_custom(base_mac_addr);
|
||||||
if (ret != ESP_OK) {
|
if (ret != ESP_OK) {
|
||||||
ret = esp_efuse_mac_get_default(base_mac_addr);
|
ret = esp_efuse_mac_get_default(base_mac_addr);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
len = MIN(len, ARRAY_SIZE(base_mac_addr));
|
||||||
memcpy(buf, (const void *)base_mac_addr, len);
|
memcpy(buf, (const void *)base_mac_addr, len);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
Loading…
Reference in New Issue