Skip to content

Commit

Permalink
AP_DroneCAN: DNAServer: avoid clearing node ID during allocation
Browse files Browse the repository at this point in the history
Not necessary and wastes flash.
  • Loading branch information
tpwrules committed Sep 9, 2024
1 parent 9726e8e commit 211f936
Showing 1 changed file with 0 additions and 3 deletions.
3 changes: 0 additions & 3 deletions libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -458,7 +458,6 @@ void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer,
(now - last_alloc_msg_ms) > 500) {
if (msg.first_part_of_unique_id) {
rcvd_unique_id_offset = 0;
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
} else {
//we are only accepting first part
return;
Expand All @@ -482,7 +481,6 @@ void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer,
if ((rcvd_unique_id_offset + msg.unique_id.len) > 16) {
//This request is malformed, Reset!
rcvd_unique_id_offset = 0;
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
return;
}

Expand All @@ -505,7 +503,6 @@ void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer,
rsp.node_id = db.handle_allocation(msg.node_id, (const uint8_t*)rcvd_unique_id);
//reset states as well
rcvd_unique_id_offset = 0;
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
}

allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD
Expand Down

0 comments on commit 211f936

Please sign in to comment.