mirror of https://github.com/ArduPilot/ardupilot
AP_OpenDroneID: only load from persistent memory in init()
we do not want to do this from update() as it is an expensive call
This commit is contained in:
parent
181505afa5
commit
fcd4152b30
|
@ -132,9 +132,6 @@ void AP_OpenDroneID::set_basic_id() {
|
|||
if (pkt_basic_id.id_type != MAV_ODID_ID_TYPE_NONE) {
|
||||
return;
|
||||
}
|
||||
if ((id_len == 0) && (_options & LockUASIDOnFirstBasicIDRx)) {
|
||||
load_UAS_ID_from_persistent_memory();
|
||||
}
|
||||
if (id_len > 0) {
|
||||
// prepare basic id pkt
|
||||
uint8_t val = gcs().sysid_this_mav();
|
||||
|
|
Loading…
Reference in New Issue