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.cpp
Views: 1798
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*14* Author: Siddharth Bharat Purohit15*/1617#include <AP_HAL/AP_HAL.h>1819#if HAL_ENABLE_DRONECAN_DRIVERS2021#include "AP_DroneCAN_DNA_Server.h"22#include "AP_DroneCAN.h"23#include <StorageManager/StorageManager.h>24#include <AP_Math/AP_Math.h>25#include <GCS_MAVLink/GCS.h>26#include <AP_Logger/AP_Logger.h>27#include <AP_BoardConfig/AP_BoardConfig.h>28#include <stdio.h>29extern const AP_HAL::HAL& hal;3031// FORMAT REVISION DREAMS (things to address if the NodeRecord needs to be changed substantially)32// * have DNA server accept only a 16 byte local UID to avoid overhead from variable sized hash33// * have a real empty flag for entries and/or use a CRC which is not zero for an input of all zeros34// * fix FNV-1a hash folding to be to 48 bits (6 bytes) instead of 563536#define NODERECORD_MAGIC 0xAC0137#define NODERECORD_MAGIC_LEN 2 // uint16_t38#define MAX_NODE_ID 12539#define NODERECORD_LOC(node_id) ((node_id * sizeof(NodeRecord)) + NODERECORD_MAGIC_LEN)4041#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)4243// database is currently shared by all DNA servers44AP_DroneCAN_DNA_Server::Database AP_DroneCAN_DNA_Server::db;4546// initialize database (storage accessor is always replaced with the one supplied)47void AP_DroneCAN_DNA_Server::Database::init(StorageAccess *storage_)48{49// storage size must be synced with StorageCANDNA entry in StorageManager.cpp50static_assert(NODERECORD_LOC(MAX_NODE_ID+1) <= 1024, "DNA storage too small");5152// might be called from multiple threads if multiple servers use the same database53WITH_SEMAPHORE(sem);5455storage = storage_; // use supplied accessor5657// validate magic number58uint16_t magic = storage->read_uint16(0);59if (magic != NODERECORD_MAGIC) {60reset(); // resetting the database will put the magic back61}6263// check and note each possible node ID's registration's presence64for (uint8_t i = 1; i <= MAX_NODE_ID; i++) {65if (check_registration(i)) {66node_registered.set(i);67}68}69}7071// remove all registrations from the database72void AP_DroneCAN_DNA_Server::Database::reset()73{74WITH_SEMAPHORE(sem);7576NodeRecord record;77memset(&record, 0, sizeof(record));78node_registered.clearall();7980// all-zero record means no registration81// ensure node ID 0 is cleared even if we can't use it so we know the state82for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {83write_record(record, i);84}8586// mark the magic at the start to indicate a valid (and reset) database87storage->write_uint16(0, NODERECORD_MAGIC);88}8990// handle initializing the server with its own node ID and unique ID91void AP_DroneCAN_DNA_Server::Database::init_server(uint8_t own_node_id, const uint8_t own_unique_id[], uint8_t own_unique_id_len)92{93WITH_SEMAPHORE(sem);9495// register server node ID and unique ID if not correctly registered. note96// that ardupilot mixes the node ID into the unique ID so changing the node97// ID will "leak" the old node ID98if (own_node_id != find_node_id(own_unique_id, own_unique_id_len)) {99register_uid(own_node_id, own_unique_id, own_unique_id_len);100}101}102103// handle processing the node info message. returns true if from a duplicate node104bool AP_DroneCAN_DNA_Server::Database::handle_node_info(uint8_t source_node_id, const uint8_t unique_id[])105{106WITH_SEMAPHORE(sem);107108if (is_registered(source_node_id)) {109// this device's node ID is associated with a different unique ID110if (source_node_id != find_node_id(unique_id, 16)) {111return true; // so raise as duplicate112}113} else {114register_uid(source_node_id, unique_id, 16); // we don't know about this node ID, let's register it115}116return false; // not a duplicate117}118119// handle the allocation message. returns the allocated node ID, or 0 if allocation failed120uint8_t AP_DroneCAN_DNA_Server::Database::handle_allocation(const uint8_t unique_id[])121{122WITH_SEMAPHORE(sem);123124uint8_t resp_node_id = find_node_id(unique_id, 16);125if (resp_node_id == 0) {126// find free node ID, starting at the max as prescribed by the standard127resp_node_id = MAX_NODE_ID;128while (resp_node_id > 0) {129if (!node_registered.get(resp_node_id)) {130break;131}132resp_node_id--;133}134135if (resp_node_id != 0) {136create_registration(resp_node_id, unique_id, 16);137}138}139return resp_node_id; // will be 0 if not found and not created140}141142// retrieve node ID that matches the given unique ID. returns 0 if not found143uint8_t AP_DroneCAN_DNA_Server::Database::find_node_id(const uint8_t unique_id[], uint8_t size)144{145NodeRecord record, cmp_record;146compute_uid_hash(cmp_record, unique_id, size);147148for (int i = MAX_NODE_ID; i > 0; i--) {149if (node_registered.get(i)) {150read_record(record, i);151if (memcmp(record.uid_hash, cmp_record.uid_hash, sizeof(NodeRecord::uid_hash)) == 0) {152return i; // node ID found153}154}155}156return 0; // not found157}158159// fill the given record with the hash of the given unique ID160void AP_DroneCAN_DNA_Server::Database::compute_uid_hash(NodeRecord &record, const uint8_t unique_id[], uint8_t size) const161{162uint64_t hash = FNV_1_OFFSET_BASIS_64;163hash_fnv_1a(size, unique_id, &hash);164165// xor-folding per http://www.isthe.com/chongo/tech/comp/fnv/166hash = (hash>>56) ^ (hash&(((uint64_t)1<<56)-1)); // 56 should be 48 since we use 6 bytes167168// write it to ret169for (uint8_t i=0; i<6; i++) {170record.uid_hash[i] = (hash >> (8*i)) & 0xff;171}172}173174// register a given unique ID to a given node ID, deleting any existing registration for the unique ID175void AP_DroneCAN_DNA_Server::Database::register_uid(uint8_t node_id, const uint8_t unique_id[], uint8_t size)176{177uint8_t prev_node_id = find_node_id(unique_id, size); // have we registered this unique ID under a different node ID?178if (prev_node_id != 0) {179delete_registration(prev_node_id); // yes, delete old node ID's registration180}181// overwrite an existing registration with this node ID, if any182create_registration(node_id, unique_id, size);183}184185// create the registration for the given node ID and set its record's unique ID186void AP_DroneCAN_DNA_Server::Database::create_registration(uint8_t node_id, const uint8_t unique_id[], uint8_t size)187{188NodeRecord record;189compute_uid_hash(record, unique_id, size);190// compute and store CRC of the record's data to validate it191record.crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash));192193write_record(record, node_id);194195node_registered.set(node_id);196}197198// delete the given node ID's registration199void AP_DroneCAN_DNA_Server::Database::delete_registration(uint8_t node_id)200{201if (node_id > MAX_NODE_ID) {202return;203}204205NodeRecord record;206207// all-zero record means no registration208memset(&record, 0, sizeof(record));209write_record(record, node_id);210node_registered.clear(node_id);211}212213// return true if the given node ID has a registration214bool AP_DroneCAN_DNA_Server::Database::check_registration(uint8_t node_id)215{216NodeRecord record;217read_record(record, node_id);218219uint8_t empty_uid[sizeof(NodeRecord::uid_hash)] {};220uint8_t crc = crc_crc8(record.uid_hash, sizeof(record.uid_hash));221if (crc == record.crc && memcmp(&record.uid_hash[0], &empty_uid[0], sizeof(empty_uid)) != 0) {222return true; // CRC matches and UID hash is not all zero223}224return false;225}226227// read the given node ID's registration's record228void AP_DroneCAN_DNA_Server::Database::read_record(NodeRecord &record, uint8_t node_id)229{230if (node_id > MAX_NODE_ID) {231return;232}233234storage->read_block(&record, NODERECORD_LOC(node_id), sizeof(NodeRecord));235}236237// write the given node ID's registration's record238void AP_DroneCAN_DNA_Server::Database::write_record(const NodeRecord &record, uint8_t node_id)239{240if (node_id > MAX_NODE_ID) {241return;242}243244storage->write_block(NODERECORD_LOC(node_id), &record, sizeof(NodeRecord));245}246247248AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index) :249storage(StorageManager::StorageCANDNA),250_ap_dronecan(ap_dronecan),251_canard_iface(canard_iface),252allocation_sub(allocation_cb, driver_index),253node_status_sub(node_status_cb, driver_index),254node_info_client(_canard_iface, node_info_cb) {}255256/* Initialises Publishers for respective UAVCAN Instance257Also resets the Server Record in case there is a mismatch258between specified node id and unique id against the existing259Server Record. */260bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id)261{262//Read the details from AP_DroneCAN263server_state = HEALTHY;264265db.init(&storage); // initialize the database with our accessor266267if (_ap_dronecan.check_and_reset_option(AP_DroneCAN::Options::DNA_CLEAR_DATABASE)) {268GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset");269db.reset();270}271272db.init_server(node_id, own_unique_id, own_unique_id_len);273274/* Also add to seen node id this is to verify275if any duplicates are on the bus carrying our Node ID */276node_seen.set(node_id);277node_verified.set(node_id);278node_healthy.set(node_id);279self_node_id = node_id;280return true;281}282283/* Run through the list of seen node ids for verification no more284than once per 5 second. We continually verify the nodes in our285seen list, So that we can raise issue if there are duplicates286on the bus. */287void AP_DroneCAN_DNA_Server::verify_nodes()288{289uint32_t now = AP_HAL::millis();290if ((now - last_verification_request) < 5000) {291return;292}293294#if HAL_LOGGING_ENABLED295uint8_t log_count = AP::logger().get_log_start_count();296if (log_count != last_logging_count) {297last_logging_count = log_count;298node_logged.clearall();299}300#endif301302//Check if we got acknowledgement from previous request303//except for requests using our own node_id304if (curr_verifying_node == self_node_id) {305nodeInfo_resp_rcvd = true;306}307308if (!nodeInfo_resp_rcvd) {309/* Also notify GCS about this310Reason for this could be either the node was disconnected311Or a node with conflicting ID appeared and is sending response312at the same time. */313node_verified.clear(curr_verifying_node);314}315316last_verification_request = now;317//Find the next registered Node ID to be verified.318for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {319curr_verifying_node = (curr_verifying_node + 1) % (MAX_NODE_ID + 1);320if ((curr_verifying_node == self_node_id) || (curr_verifying_node == 0)) {321continue;322}323if (node_seen.get(curr_verifying_node)) {324break;325}326}327if (db.is_registered(curr_verifying_node)) {328uavcan_protocol_GetNodeInfoRequest request;329node_info_client.request(curr_verifying_node, request);330nodeInfo_resp_rcvd = false;331}332}333334/* Handles Node Status Message, adds to the Seen Node list335Also starts the Service call for Node Info to complete the336Verification process. */337void AP_DroneCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg)338{339if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) {340return;341}342if ((msg.health != UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK ||343msg.mode != UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL) &&344!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {345//if node is not healthy or operational, clear resp health mask, and set fault_node_id346fault_node_id = transfer.source_node_id;347server_state = NODE_STATUS_UNHEALTHY;348node_healthy.clear(transfer.source_node_id);349} else {350node_healthy.set(transfer.source_node_id);351if (node_healthy == node_verified) {352server_state = HEALTHY;353}354}355if (!node_verified.get(transfer.source_node_id)) {356//immediately begin verification of the node_id357uavcan_protocol_GetNodeInfoRequest request;358node_info_client.request(transfer.source_node_id, request);359}360//Add node to seen list if not seen before361node_seen.set(transfer.source_node_id);362}363364/* Node Info message handler365Handle responses from GetNodeInfo Request. We verify the node info366against our records. Marks Verification mask if already recorded,367Or register if the node id is available and not recorded for the368received Unique ID */369void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp)370{371if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) {372return;373}374/*375if we haven't logged this node then log it now376*/377#if HAL_LOGGING_ENABLED378if (!node_logged.get(transfer.source_node_id) && AP::logger().logging_started()) {379node_logged.set(transfer.source_node_id);380uint64_t uid[2];381memcpy(uid, rsp.hardware_version.unique_id, sizeof(rsp.hardware_version.unique_id));382// @LoggerMessage: CAND383// @Description: Info from GetNodeInfo request384// @Field: TimeUS: Time since system startup385// @Field: Driver: Driver index386// @Field: NodeId: Node ID387// @Field: UID1: Hardware ID, part 1388// @Field: UID2: Hardware ID, part 2389// @Field: Name: Name string390// @Field: Major: major revision id391// @Field: Minor: minor revision id392// @Field: Version: AP_Periph git hash393AP::logger().Write("CAND", "TimeUS,Driver,NodeId,UID1,UID2,Name,Major,Minor,Version",394"s-#------", "F--------", "QBBQQZBBI",395AP_HAL::micros64(),396_ap_dronecan.get_driver_index(),397transfer.source_node_id,398uid[0], uid[1],399rsp.name.data,400rsp.software_version.major,401rsp.software_version.minor,402rsp.software_version.vcs_commit);403}404#endif405406bool duplicate = db.handle_node_info(transfer.source_node_id, rsp.hardware_version.unique_id);407if (duplicate) {408if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {409/* This is a device with node_id already registered410for another device */411server_state = DUPLICATE_NODES;412fault_node_id = transfer.source_node_id;413memcpy(fault_node_name, rsp.name.data, sizeof(fault_node_name));414}415} else {416//Verify as well417node_verified.set(transfer.source_node_id);418if (transfer.source_node_id == curr_verifying_node) {419nodeInfo_resp_rcvd = true;420}421}422}423424// process node ID allocation messages for DNA425void AP_DroneCAN_DNA_Server::handle_allocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg)426{427if (transfer.source_node_id != 0) {428return; // ignore allocation messages that are not DNA requests429}430uint32_t now = AP_HAL::millis();431432if ((now - last_alloc_msg_ms) > UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_FOLLOWUP_TIMEOUT_MS) {433rcvd_unique_id_offset = 0; // reset state, timed out434}435436if (msg.first_part_of_unique_id) {437// nodes waiting to send a follow up will instead send a first part438// again if they see another allocation message. therefore we should439// always reset and process a received first part, since any node we440// were allocating will never send its follow up and we'd just time out441rcvd_unique_id_offset = 0;442} else if (rcvd_unique_id_offset == 0) {443return; // not first part but we are expecting one, ignore444}445446if (rcvd_unique_id_offset) {447debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting Followup part! %u\n",448(unsigned long)now,449unsigned((now - last_alloc_msg_ms)));450} else {451debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %lu -- Accepting First part! %u\n",452(unsigned long)now,453unsigned((now - last_alloc_msg_ms)));454}455456last_alloc_msg_ms = now;457if ((rcvd_unique_id_offset + msg.unique_id.len) > sizeof(rcvd_unique_id)) {458rcvd_unique_id_offset = 0; // reset state, request contains an over-long ID459return;460}461462// save the new portion of the unique ID463memcpy(&rcvd_unique_id[rcvd_unique_id_offset], msg.unique_id.data, msg.unique_id.len);464rcvd_unique_id_offset += msg.unique_id.len;465466// respond with the message containing the received unique ID so far, or467// with the node ID if we successfully allocated one468uavcan_protocol_dynamic_node_id_Allocation rsp {};469memcpy(rsp.unique_id.data, rcvd_unique_id, rcvd_unique_id_offset);470rsp.unique_id.len = rcvd_unique_id_offset;471472if (rcvd_unique_id_offset == sizeof(rcvd_unique_id)) { // full unique ID received, allocate it!473// we ignore the preferred node ID as it seems nobody uses the feature474// and we couldn't guarantee it anyway. we will always remember and475// re-assign node IDs consistently, so the node could send a status476// with a particular ID once then switch back to no preference for DNA477rsp.node_id = db.handle_allocation(rcvd_unique_id);478rcvd_unique_id_offset = 0; // reset state for next allocation479if (rsp.node_id == 0) { // allocation failed480GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DroneCAN DNA allocation failed; database full");481// don't send reply with a failed ID in case the allocatee does482// silly things, though it is technically legal. the allocatee will483// then time out and try again (though we still won't have an ID!)484return;485}486}487488allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD489}490491//report the server state, along with failure message if any492bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) const493{494switch (server_state) {495case HEALTHY:496return true;497case DUPLICATE_NODES: {498if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {499// ignore error500return true;501}502snprintf(fail_msg, fail_msg_len, "Duplicate Node %s../%d!", fault_node_name, fault_node_id);503return false;504}505case NODE_STATUS_UNHEALTHY: {506if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {507// ignore error508return true;509}510snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id);511return false;512}513}514// should never get; compiler should enforce all server_states are covered515return false;516}517518#endif //HAL_NUM_CAN_IFACES519520521