mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: DNA_Server: make reset method private
This commit is contained in:
parent
6b4e11090c
commit
c1f59186fa
|
@ -62,6 +62,9 @@ class AP_DroneCAN_DNA_Server
|
|||
//Generates 6Byte long hash from the specified unique_id
|
||||
void getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const;
|
||||
|
||||
//Reset the Server Record
|
||||
void reset();
|
||||
|
||||
//Reads the Server Record from storage for specified node id
|
||||
bool readNodeData(NodeData &data, uint8_t node_id);
|
||||
|
||||
|
@ -113,9 +116,6 @@ public:
|
|||
//Initialises publisher and Server Record for specified uavcan driver
|
||||
bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id);
|
||||
|
||||
//Reset the Server Record
|
||||
void reset();
|
||||
|
||||
/* Checks if the node id has been verified against the record
|
||||
Specific CAN drivers are expected to check use this method to
|
||||
verify if the node is healthy and has static node_id against
|
||||
|
|
Loading…
Reference in New Issue