diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 17e32a4995..deb5f8c8a2 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -197,20 +197,8 @@ bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id db.reset(); } - // Making sure that the server is started with the same node ID - const uint8_t stored_own_node_id = db.getNodeIDForUniqueID(own_unique_id, own_unique_id_len); - static bool reset_done; - if (stored_own_node_id != node_id) { // cannot match if not found - // We have no matching record of our own Unique ID do a reset - if (!reset_done) { - /* ensure we only reset once per power cycle - else we will wipe own record on next init(s) */ - db.reset(); - reset_done = true; - } - //Add ourselves to the Server Record - db.addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len); - } + db.initServer(node_id, own_unique_id, own_unique_id_len); + /* Also add to seen node id this is to verify if any duplicates are on the bus carrying our Node ID */ node_seen.set(node_id); @@ -220,6 +208,27 @@ bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id return true; } +// handle initializing the server with the given expected node ID and unique ID +void AP_DroneCAN_DNA_Server::Database::initServer(uint8_t node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len) +{ + WITH_SEMAPHORE(sem); + + // Making sure that the server is started with the same node ID + const uint8_t stored_own_node_id = getNodeIDForUniqueID(own_unique_id, own_unique_id_len); + static bool reset_done; + if (stored_own_node_id != node_id) { // cannot match if not found + // We have no matching record of our own Unique ID do a reset + if (!reset_done) { + /* ensure we only reset once per power cycle + else we will wipe own record on next init(s) */ + reset(); + reset_done = true; + } + //Add ourselves to the Server Record + addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len); + } +} + //Reset the Server Records void AP_DroneCAN_DNA_Server::Database::reset() diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h index 577f4f2993..a7ad68cc4d 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h @@ -38,6 +38,9 @@ class AP_DroneCAN_DNA_Server return node_storage_occupied.get(node_id); } + // handle initializing the server with the given expected node ID and unique ID + void initServer(uint8_t node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len); + //Generates 6Byte long hash from the specified unique_id void getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const;