mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_DroneCAN: DNA_Server: make lower level database tasks private
All the higher level database operations need to be locked for the whole duration of the operation, so nobody should be using the lower-level tasks or raw read/write functions. We can also remove the locks from them. The database can now safely be used by multiple servers.
This commit is contained in:
parent
4097e9fa42
commit
e12f345bae
@ -74,7 +74,6 @@ void AP_DroneCAN_DNA_Server::Database::readNodeData(NodeData &data, uint8_t node
|
||||
return;
|
||||
}
|
||||
|
||||
WITH_SEMAPHORE(sem);
|
||||
storage->read_block(&data, NODEDATA_LOC(node_id), sizeof(struct NodeData));
|
||||
}
|
||||
|
||||
@ -85,7 +84,6 @@ void AP_DroneCAN_DNA_Server::Database::writeNodeData(const NodeData &data, uint8
|
||||
return;
|
||||
}
|
||||
|
||||
WITH_SEMAPHORE(sem);
|
||||
storage->write_block(NODEDATA_LOC(node_id), &data, sizeof(struct NodeData));
|
||||
}
|
||||
|
||||
|
@ -47,6 +47,7 @@ class AP_DroneCAN_DNA_Server
|
||||
// handle the allocation message. returns the new node ID.
|
||||
uint8_t handleAllocation(uint8_t node_id, const uint8_t unique_id[]);
|
||||
|
||||
private:
|
||||
//Generates 6Byte long hash from the specified unique_id
|
||||
void getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const;
|
||||
|
||||
@ -62,7 +63,6 @@ class AP_DroneCAN_DNA_Server
|
||||
//Finds next available free Node, starting from preferred NodeID
|
||||
uint8_t findFreeNodeID(uint8_t preferred);
|
||||
|
||||
private:
|
||||
//Look in the storage and check if there's a valid Server Record there
|
||||
bool isValidNodeDataAvailable(uint8_t node_id);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user