2019-09-21 00:16:06 -03:00
|
|
|
#pragma once
|
2022-02-28 21:19:20 -04:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
#include <AP_HAL/Semaphores.h>
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
#if HAL_ENABLE_DRONECAN_DRIVERS
|
2019-09-21 00:16:06 -03:00
|
|
|
#include <AP_Common/Bitmask.h>
|
|
|
|
#include <StorageManager/StorageManager.h>
|
2020-05-31 09:47:45 -03:00
|
|
|
#include <AP_CANManager/AP_CANManager.h>
|
2023-01-04 21:09:23 -04:00
|
|
|
#include <canard/publisher.h>
|
|
|
|
#include <canard/subscriber.h>
|
|
|
|
#include <canard/service_client.h>
|
|
|
|
#include "AP_Canard_iface.h"
|
|
|
|
#include <dronecan_msgs.h>
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
class AP_DroneCAN;
|
2023-01-04 21:09:23 -04:00
|
|
|
//Forward declaring classes
|
2023-04-06 21:18:01 -03:00
|
|
|
class AP_DroneCAN_DNA_Server
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
StorageAccess storage;
|
|
|
|
|
|
|
|
struct NodeData {
|
|
|
|
uint8_t hwid_hash[6];
|
|
|
|
uint8_t crc;
|
|
|
|
};
|
|
|
|
|
2024-08-05 12:31:01 -03:00
|
|
|
class Database {
|
|
|
|
public:
|
|
|
|
Database() {};
|
|
|
|
|
|
|
|
// initialize database (storage accessor is always replaced with the one supplied)
|
|
|
|
void init(StorageAccess *storage_);
|
|
|
|
|
|
|
|
//Reset the Server Record
|
|
|
|
void reset();
|
|
|
|
|
2024-08-05 12:39:37 -03:00
|
|
|
// returns true if the given node ID is occupied (has valid stored data)
|
|
|
|
bool isOccupied(uint8_t node_id) {
|
|
|
|
return node_storage_occupied.get(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
//Generates 6Byte long hash from the specified unique_id
|
|
|
|
void getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const;
|
|
|
|
|
|
|
|
//Methods to set, clear and report NodeIDs allocated/registered so far
|
|
|
|
void freeNodeID(uint8_t node_id);
|
|
|
|
|
|
|
|
//Go through List to find node id for specified unique id
|
|
|
|
uint8_t getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size);
|
|
|
|
|
|
|
|
//Add Node ID info to the record and setup necessary mask fields
|
|
|
|
void addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size);
|
|
|
|
|
|
|
|
//Finds next available free Node, starting from preferred NodeID
|
|
|
|
uint8_t findFreeNodeID(uint8_t preferred);
|
|
|
|
|
|
|
|
private:
|
2024-08-05 12:31:01 -03:00
|
|
|
//Look in the storage and check if there's a valid Server Record there
|
|
|
|
bool isValidNodeDataAvailable(uint8_t node_id);
|
|
|
|
|
|
|
|
//Reads the Server Record from storage for specified node id
|
|
|
|
void readNodeData(NodeData &data, uint8_t node_id);
|
|
|
|
|
|
|
|
//Writes the Server Record from storage for specified node id
|
|
|
|
void writeNodeData(const NodeData &data, uint8_t node_id);
|
|
|
|
|
|
|
|
// bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID)
|
|
|
|
Bitmask<128> node_storage_occupied; // storage has a valid entry
|
|
|
|
|
|
|
|
StorageAccess *storage;
|
|
|
|
HAL_Semaphore sem;
|
|
|
|
};
|
|
|
|
|
|
|
|
static Database db;
|
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
enum ServerState {
|
2022-04-29 08:47:51 -03:00
|
|
|
NODE_STATUS_UNHEALTHY = -5,
|
2019-09-21 00:16:06 -03:00
|
|
|
DUPLICATE_NODES = -2,
|
|
|
|
HEALTHY = 0
|
|
|
|
};
|
|
|
|
|
|
|
|
uint32_t last_verification_request;
|
|
|
|
uint8_t curr_verifying_node;
|
2023-01-04 21:09:23 -04:00
|
|
|
uint8_t self_node_id;
|
2019-09-21 00:16:06 -03:00
|
|
|
bool nodeInfo_resp_rcvd;
|
|
|
|
|
2024-07-13 16:59:20 -03:00
|
|
|
// bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID)
|
|
|
|
Bitmask<128> node_verified; // node seen and unique ID matches stored
|
|
|
|
Bitmask<128> node_seen; // received NodeStatus
|
|
|
|
Bitmask<128> node_logged; // written to log fle
|
|
|
|
Bitmask<128> node_healthy; // reports healthy
|
2020-12-31 17:04:08 -04:00
|
|
|
|
|
|
|
uint8_t last_logging_count;
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
//Error State
|
|
|
|
enum ServerState server_state;
|
|
|
|
uint8_t fault_node_id;
|
|
|
|
char fault_node_name[15];
|
|
|
|
|
|
|
|
|
|
|
|
//Allocation params
|
|
|
|
uint8_t rcvd_unique_id[16];
|
|
|
|
uint8_t rcvd_unique_id_offset;
|
2020-05-31 09:47:45 -03:00
|
|
|
uint32_t last_alloc_msg_ms;
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
AP_DroneCAN &_ap_dronecan;
|
2023-01-04 21:09:23 -04:00
|
|
|
CanardInterface &_canard_iface;
|
2022-04-04 07:33:33 -03:00
|
|
|
|
2023-01-04 21:09:23 -04:00
|
|
|
Canard::Publisher<uavcan_protocol_dynamic_node_id_Allocation> allocation_pub{_canard_iface};
|
2022-04-04 07:33:33 -03:00
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_dynamic_node_id_Allocation> allocation_cb{this, &AP_DroneCAN_DNA_Server::handleAllocation};
|
2023-01-04 21:09:23 -04:00
|
|
|
Canard::Subscriber<uavcan_protocol_dynamic_node_id_Allocation> allocation_sub;
|
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_NodeStatus> node_status_cb{this, &AP_DroneCAN_DNA_Server::handleNodeStatus};
|
2023-01-04 21:09:23 -04:00
|
|
|
Canard::Subscriber<uavcan_protocol_NodeStatus> node_status_sub;
|
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_GetNodeInfoResponse> node_info_cb{this, &AP_DroneCAN_DNA_Server::handleNodeInfo};
|
2023-01-04 21:09:23 -04:00
|
|
|
Canard::Client<uavcan_protocol_GetNodeInfoResponse> node_info_client;
|
2020-01-15 19:49:41 -04:00
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
public:
|
2023-07-28 00:25:04 -03:00
|
|
|
AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index);
|
2022-04-04 07:33:33 -03:00
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
// Do not allow copies
|
2023-04-06 21:18:01 -03:00
|
|
|
CLASS_NO_COPY(AP_DroneCAN_DNA_Server);
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
//Initialises publisher and Server Record for specified uavcan driver
|
2023-01-04 21:09:23 -04:00
|
|
|
bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id);
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
/* Subscribe to the messages to be handled for maintaining and allocating
|
|
|
|
Node ID list */
|
2023-04-06 21:18:01 -03:00
|
|
|
static void subscribe_msgs(AP_DroneCAN* ap_dronecan);
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
//report the server state, along with failure message if any
|
|
|
|
bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const;
|
|
|
|
|
|
|
|
//Callbacks
|
2023-01-04 21:09:23 -04:00
|
|
|
void handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg);
|
|
|
|
void handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg);
|
|
|
|
void handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp);
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
//Run through the list of seen node ids for verification
|
2022-04-04 07:33:33 -03:00
|
|
|
void verify_nodes();
|
2019-09-21 00:16:06 -03:00
|
|
|
};
|
|
|
|
|
2019-10-25 00:03:16 -03:00
|
|
|
#endif
|