Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h
Views: 1798
#pragma once1#include <AP_HAL/AP_HAL_Boards.h>2#include <AP_HAL/Semaphores.h>34#if HAL_ENABLE_DRONECAN_DRIVERS5#include <AP_Common/Bitmask.h>6#include <StorageManager/StorageManager.h>7#include <AP_CANManager/AP_CANManager.h>8#include <canard/publisher.h>9#include <canard/subscriber.h>10#include <canard/service_client.h>11#include "AP_Canard_iface.h"12#include <dronecan_msgs.h>1314class AP_DroneCAN;15//Forward declaring classes16class AP_DroneCAN_DNA_Server17{18StorageAccess storage;1920struct NodeRecord {21uint8_t uid_hash[6];22uint8_t crc;23};2425/*26* For each node ID (1 through MAX_NODE_ID), the database can have one27* registration for it. Each registration consists of a NodeRecord which28* contains the (hash of the) unique ID reported by that node ID. Other29* info could be added to the registration in the future.30*31* Physically, the database is stored as a header and format version,32* followed by an array of NodeRecords indexed by node ID. If a particular33* NodeRecord has an all-zero unique ID hash or an invalid CRC, then that34* node ID isn't considerd to have a registration.35*36* The database has public methods which handle the server behavior for the37* relevant message. The methods can be used by multiple servers in38* different threads, so each holds a lock for its duration.39*/40class Database {41public:42Database() {};4344// initialize database (storage accessor is always replaced with the one supplied)45void init(StorageAccess *storage_);4647// remove all registrations from the database48void reset();4950// return true if the given node ID is registered51bool is_registered(uint8_t node_id) {52return node_registered.get(node_id);53}5455// handle initializing the server with its own node ID and unique ID56void init_server(uint8_t own_node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len);5758// handle processing the node info message. returns true if from a duplicate node59bool handle_node_info(uint8_t source_node_id, const uint8_t unique_id[]);6061// handle the allocation message. returns the allocated node ID, or 0 if allocation failed62uint8_t handle_allocation(const uint8_t unique_id[]);6364private:65// retrieve node ID that matches the given unique ID. returns 0 if not found66uint8_t find_node_id(const uint8_t unique_id[], uint8_t size);6768// fill the given record with the hash of the given unique ID69void compute_uid_hash(NodeRecord &record, const uint8_t unique_id[], uint8_t size) const;7071// register a given unique ID to a given node ID, deleting any existing registration for the unique ID72void register_uid(uint8_t node_id, const uint8_t unique_id[], uint8_t size);7374// create the registration for the given node ID and set its record's unique ID75void create_registration(uint8_t node_id, const uint8_t unique_id[], uint8_t size);7677// delete the given node ID's registration78void delete_registration(uint8_t node_id);7980// return true if the given node ID has a registration81bool check_registration(uint8_t node_id);8283// read the given node ID's registration's record84void read_record(NodeRecord &record, uint8_t node_id);8586// write the given node ID's registration's record87void write_record(const NodeRecord &record, uint8_t node_id);8889// bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID)90Bitmask<128> node_registered; // have a registration for this node ID9192StorageAccess *storage;93HAL_Semaphore sem;94};9596static Database db;9798enum ServerState {99NODE_STATUS_UNHEALTHY = -5,100DUPLICATE_NODES = -2,101HEALTHY = 0102};103104uint32_t last_verification_request;105uint8_t curr_verifying_node;106uint8_t self_node_id;107bool nodeInfo_resp_rcvd;108109// bitmasks containing a status for each possible node ID (except 0 and > MAX_NODE_ID)110Bitmask<128> node_verified; // node seen and unique ID matches stored111Bitmask<128> node_seen; // received NodeStatus112Bitmask<128> node_logged; // written to log fle113Bitmask<128> node_healthy; // reports healthy114115uint8_t last_logging_count;116117//Error State118enum ServerState server_state;119uint8_t fault_node_id;120char fault_node_name[15];121122123// dynamic node ID allocation state variables124uint8_t rcvd_unique_id[16];125uint8_t rcvd_unique_id_offset;126uint32_t last_alloc_msg_ms;127128AP_DroneCAN &_ap_dronecan;129CanardInterface &_canard_iface;130131Canard::Publisher<uavcan_protocol_dynamic_node_id_Allocation> allocation_pub{_canard_iface};132133Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_dynamic_node_id_Allocation> allocation_cb{this, &AP_DroneCAN_DNA_Server::handle_allocation};134Canard::Subscriber<uavcan_protocol_dynamic_node_id_Allocation> allocation_sub;135136Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_NodeStatus> node_status_cb{this, &AP_DroneCAN_DNA_Server::handleNodeStatus};137Canard::Subscriber<uavcan_protocol_NodeStatus> node_status_sub;138139Canard::ObjCallback<AP_DroneCAN_DNA_Server, uavcan_protocol_GetNodeInfoResponse> node_info_cb{this, &AP_DroneCAN_DNA_Server::handleNodeInfo};140Canard::Client<uavcan_protocol_GetNodeInfoResponse> node_info_client;141142public:143AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index);144145146// Do not allow copies147CLASS_NO_COPY(AP_DroneCAN_DNA_Server);148149//Initialises publisher and Server Record for specified uavcan driver150bool init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id);151152//report the server state, along with failure message if any153bool prearm_check(char* fail_msg, uint8_t fail_msg_len) const;154155// canard message handler callbacks156void handle_allocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg);157void handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg);158void handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp);159160//Run through the list of seen node ids for verification161void verify_nodes();162};163164#endif165166167