2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*
|
|
|
|
* Author: Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
2023-04-08 01:09:10 -03:00
|
|
|
#if HAL_ENABLE_DRONECAN_DRIVERS
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2023-04-06 21:18:01 -03:00
|
|
|
#include "AP_DroneCAN_DNA_Server.h"
|
|
|
|
#include "AP_DroneCAN.h"
|
2019-09-21 00:16:06 -03:00
|
|
|
#include <StorageManager/StorageManager.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2020-12-31 17:04:08 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2021-09-29 04:36:41 -03:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2023-01-04 21:09:23 -04:00
|
|
|
#include <stdio.h>
|
2019-09-21 00:16:06 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#define NODEDATA_MAGIC 0xAC01
|
|
|
|
#define NODEDATA_MAGIC_LEN 2
|
|
|
|
#define MAX_NODE_ID 125
|
|
|
|
|
2023-04-08 01:27:51 -03:00
|
|
|
#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2023-07-28 00:25:04 -03:00
|
|
|
AP_DroneCAN_DNA_Server::AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index) :
|
2023-04-06 21:18:01 -03:00
|
|
|
_ap_dronecan(ap_dronecan),
|
2023-07-28 00:25:04 -03:00
|
|
|
_canard_iface(canard_iface),
|
2023-01-04 21:09:23 -04:00
|
|
|
storage(StorageManager::StorageCANDNA),
|
2023-07-28 00:25:04 -03:00
|
|
|
allocation_sub(allocation_cb, driver_index),
|
|
|
|
node_status_sub(node_status_cb, driver_index),
|
2023-01-04 21:09:23 -04:00
|
|
|
node_info_client(_canard_iface, node_info_cb)
|
2022-04-04 07:33:33 -03:00
|
|
|
{}
|
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
/* Method to generate 6byte hash from the Unique ID.
|
|
|
|
We return it packed inside the referenced NodeData structure */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::getHash(NodeData &node_data, const uint8_t unique_id[], uint8_t size) const
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
uint64_t hash = FNV_1_OFFSET_BASIS_64;
|
|
|
|
hash_fnv_1a(size, unique_id, &hash);
|
|
|
|
|
|
|
|
// xor-folding per http://www.isthe.com/chongo/tech/comp/fnv/
|
|
|
|
hash = (hash>>56) ^ (hash&(((uint64_t)1<<56)-1));
|
|
|
|
|
|
|
|
// write it to ret
|
|
|
|
for (uint8_t i=0; i<6; i++) {
|
|
|
|
node_data.hwid_hash[i] = (hash >> (8*i)) & 0xff;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
//Read Node Data from Storage Region
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::readNodeData(NodeData &data, uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
2022-04-04 07:33:33 -03:00
|
|
|
WITH_SEMAPHORE(storage_sem);
|
2019-09-21 00:16:06 -03:00
|
|
|
if (!storage.read_block(&data, (node_id * sizeof(struct NodeData)) + NODEDATA_MAGIC_LEN, sizeof(struct NodeData))) {
|
|
|
|
//This will fall through to Prearm Check
|
|
|
|
server_state = STORAGE_FAILURE;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
//Write Node Data to Storage Region
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::writeNodeData(const NodeData &data, uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
2022-04-04 07:33:33 -03:00
|
|
|
WITH_SEMAPHORE(storage_sem);
|
2019-09-21 00:16:06 -03:00
|
|
|
if (!storage.write_block((node_id * sizeof(struct NodeData)) + NODEDATA_MAGIC_LEN,
|
|
|
|
&data, sizeof(struct NodeData))) {
|
|
|
|
server_state = STORAGE_FAILURE;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Set Occupation Mask, handy for keeping track of all node ids that
|
|
|
|
are allocated and all that are available. */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::setOccupationMask(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
occupation_mask.set(node_id);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Remove Node Data from Server Record in Storage,
|
|
|
|
and also clear Occupation Mask */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::freeNodeID(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct NodeData node_data;
|
|
|
|
|
|
|
|
//Eliminate from Server Record
|
|
|
|
memset(&node_data, 0, sizeof(node_data));
|
|
|
|
writeNodeData(node_data, node_id);
|
|
|
|
|
|
|
|
//Clear Occupation Mask
|
|
|
|
occupation_mask.clear(node_id);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Sets the verification mask. This is to be called, once
|
|
|
|
The Seen Node has been both registered and verified against the
|
|
|
|
Server Records. */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::setVerificationMask(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
verified_mask.set(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Checks if the NodeID is occupied, i.e. its recorded
|
|
|
|
in the Server Records against a unique ID */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::isNodeIDOccupied(uint8_t node_id) const
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return occupation_mask.get(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Checks if NodeID is verified, i.e. the unique id in
|
|
|
|
Storage Records matches the one provided by Device with this node id. */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::isNodeIDVerified(uint8_t node_id) const
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return verified_mask.get(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Go through Server Records, and fetch node id that matches the provided
|
|
|
|
Unique IDs hash.
|
|
|
|
Returns 255 if no Node ID was detected */
|
2023-04-06 21:18:01 -03:00
|
|
|
uint8_t AP_DroneCAN_DNA_Server::getNodeIDForUniqueID(const uint8_t unique_id[], uint8_t size)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
uint8_t node_id = 255;
|
|
|
|
NodeData node_data, cmp_node_data;
|
|
|
|
getHash(cmp_node_data, unique_id, size);
|
|
|
|
|
|
|
|
for (int i = MAX_NODE_ID; i >= 0; i--) {
|
|
|
|
if (!isNodeIDOccupied(i)) { // No point in checking NodeID that's not taken
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (!readNodeData(node_data, i)) {
|
|
|
|
break; //Storage module has failed, report that as no NodeID detected
|
|
|
|
}
|
|
|
|
if (memcmp(node_data.hwid_hash, cmp_node_data.hwid_hash, sizeof(NodeData::hwid_hash)) == 0) {
|
|
|
|
node_id = i;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return node_id;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Hash the Unique ID and add it to the Server Record
|
|
|
|
for specified Node ID. */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::addNodeIDForUniqueID(uint8_t node_id, const uint8_t unique_id[], uint8_t size)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
NodeData node_data;
|
|
|
|
getHash(node_data, unique_id, size);
|
|
|
|
//Generate CRC for validating the data when read back
|
|
|
|
node_data.crc = crc_crc8(node_data.hwid_hash, sizeof(node_data.hwid_hash));
|
|
|
|
|
|
|
|
//Write Data to the records
|
|
|
|
if (!writeNodeData(node_data, node_id)) {
|
|
|
|
server_state = FAILED_TO_ADD_NODE;
|
|
|
|
fault_node_id = node_id;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
setOccupationMask(node_id);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
//Checks if a valid Server Record is present for specified Node ID
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::isValidNodeDataAvailable(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
NodeData node_data;
|
|
|
|
readNodeData(node_data, node_id);
|
|
|
|
uint8_t crc = crc_crc8(node_data.hwid_hash, sizeof(node_data.hwid_hash));
|
|
|
|
if (crc == node_data.crc && node_data.crc != 0) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Initialises Publishers for respective UAVCAN Instance
|
|
|
|
Also resets the Server Record in case there is a mismatch
|
|
|
|
between specified node id and unique id against the existing
|
|
|
|
Server Record. */
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::init(uint8_t own_unique_id[], uint8_t own_unique_id_len, uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
2023-04-06 21:18:01 -03:00
|
|
|
//Read the details from AP_DroneCAN
|
2019-09-21 00:16:06 -03:00
|
|
|
server_state = HEALTHY;
|
|
|
|
/* Go through our records and look for valid NodeData, to initialise
|
|
|
|
occupation mask */
|
|
|
|
for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {
|
|
|
|
if (isValidNodeDataAvailable(i)) {
|
|
|
|
occupation_mask.set(i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// Check if the magic is present
|
|
|
|
uint16_t magic;
|
2022-04-04 07:33:33 -03:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(storage_sem);
|
|
|
|
storage.read_block(&magic, 0, NODEDATA_MAGIC_LEN);
|
|
|
|
}
|
2019-09-21 00:16:06 -03:00
|
|
|
if (magic != NODEDATA_MAGIC) {
|
|
|
|
//Its not there a reset should write it in the Storage
|
|
|
|
reset();
|
|
|
|
}
|
2023-04-06 21:18:01 -03:00
|
|
|
if (_ap_dronecan.check_and_reset_option(AP_DroneCAN::Options::DNA_CLEAR_DATABASE)) {
|
2021-09-10 23:47:02 -03:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UC DNA database reset");
|
|
|
|
reset();
|
|
|
|
}
|
2019-09-21 00:16:06 -03:00
|
|
|
// Making sure that the server is started with the same node ID
|
|
|
|
const uint8_t stored_own_node_id = getNodeIDForUniqueID(own_unique_id, own_unique_id_len);
|
|
|
|
static bool reset_done;
|
|
|
|
if (stored_own_node_id != 255) {
|
|
|
|
if (stored_own_node_id != node_id) {
|
|
|
|
/* We have a different node id recorded against our own unique id
|
|
|
|
This calls for a reset */
|
|
|
|
if (!reset_done) {
|
|
|
|
/* ensure we only reset once per power cycle
|
|
|
|
else we will wipe own record on next init(s) */
|
|
|
|
reset();
|
|
|
|
reset_done = true;
|
|
|
|
}
|
|
|
|
//Add ourselves to the Server Record
|
|
|
|
if (!addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
//We have no record of our own Unique ID do a reset
|
|
|
|
if (!reset_done) {
|
|
|
|
/* ensure we only reset once per power cycle
|
|
|
|
else we will wipe own record on next init(s) */
|
|
|
|
reset();
|
|
|
|
reset_done = true;
|
|
|
|
}
|
|
|
|
//Add ourselves to the Server Record
|
|
|
|
if (!addNodeIDForUniqueID(node_id, own_unique_id, own_unique_id_len)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
/* Also add to seen node id this is to verify
|
|
|
|
if any duplicates are on the bus carrying our Node ID */
|
|
|
|
addToSeenNodeMask(node_id);
|
|
|
|
setVerificationMask(node_id);
|
2022-04-29 08:47:51 -03:00
|
|
|
node_healthy_mask.set(node_id);
|
2023-01-04 21:09:23 -04:00
|
|
|
self_node_id = node_id;
|
2019-09-21 00:16:06 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
//Reset the Server Records
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::reset()
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
NodeData node_data;
|
|
|
|
memset(&node_data, 0, sizeof(node_data));
|
|
|
|
occupation_mask.clearall();
|
|
|
|
|
|
|
|
//Just write empty Node Data to the Records
|
|
|
|
for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {
|
|
|
|
writeNodeData(node_data, i);
|
|
|
|
}
|
2022-04-04 07:33:33 -03:00
|
|
|
WITH_SEMAPHORE(storage_sem);
|
2019-09-21 00:16:06 -03:00
|
|
|
//Ensure we mark magic at the end
|
|
|
|
uint16_t magic = NODEDATA_MAGIC;
|
|
|
|
storage.write_block(0, &magic, NODEDATA_MAGIC_LEN);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Go through the Occupation mask for available Node ID
|
|
|
|
based on pseudo code provided in
|
|
|
|
uavcan/protocol/dynamic_node_id/1.Allocation.uavcan */
|
2023-04-06 21:18:01 -03:00
|
|
|
uint8_t AP_DroneCAN_DNA_Server::findFreeNodeID(uint8_t preferred)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
// Search up
|
|
|
|
uint8_t candidate = (preferred > 0) ? preferred : 125;
|
|
|
|
while (candidate <= 125) {
|
|
|
|
if (!isNodeIDOccupied(candidate)) {
|
|
|
|
return candidate;
|
|
|
|
}
|
|
|
|
candidate++;
|
|
|
|
}
|
|
|
|
//Search down
|
|
|
|
candidate = (preferred > 0) ? preferred : 125;
|
|
|
|
while (candidate > 0) {
|
|
|
|
if (!isNodeIDOccupied(candidate)) {
|
|
|
|
return candidate;
|
|
|
|
}
|
|
|
|
candidate--;
|
|
|
|
}
|
|
|
|
// Not found
|
|
|
|
return 255;
|
|
|
|
}
|
|
|
|
|
|
|
|
//Check if we have received Node Status from this node_id
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::isNodeSeen(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return node_seen_mask.get(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Set the Seen Node Mask, to be called when received
|
|
|
|
Node Status from the node id */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::addToSeenNodeMask(uint8_t node_id)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
if (node_id > MAX_NODE_ID) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
node_seen_mask.set(node_id);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Run through the list of seen node ids for verification no more
|
|
|
|
than once per 5 second. We continually verify the nodes in our
|
|
|
|
seen list, So that we can raise issue if there are duplicates
|
|
|
|
on the bus. */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::verify_nodes()
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
2023-01-04 21:09:23 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2019-09-21 00:16:06 -03:00
|
|
|
if ((now - last_verification_request) < 5000) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2023-07-13 21:58:05 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2020-12-31 17:04:08 -04:00
|
|
|
uint8_t log_count = AP::logger().get_log_start_count();
|
|
|
|
if (log_count != last_logging_count) {
|
|
|
|
last_logging_count = log_count;
|
|
|
|
logged.clearall();
|
|
|
|
}
|
2023-07-13 21:58:05 -03:00
|
|
|
#endif
|
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
//Check if we got acknowledgement from previous request
|
|
|
|
//except for requests using our own node_id
|
2023-01-04 21:09:23 -04:00
|
|
|
if (curr_verifying_node == self_node_id) {
|
2022-04-04 07:33:33 -03:00
|
|
|
nodeInfo_resp_rcvd = true;
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
2022-04-04 07:33:33 -03:00
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
if (!nodeInfo_resp_rcvd) {
|
|
|
|
/* Also notify GCS about this
|
|
|
|
Reason for this could be either the node was disconnected
|
|
|
|
Or a node with conflicting ID appeared and is sending response
|
|
|
|
at the same time. */
|
|
|
|
/* Only report if the node was verified, otherwise ignore
|
|
|
|
as this could be just Bootloader to Application transition. */
|
|
|
|
if (isNodeIDVerified(curr_verifying_node)) {
|
|
|
|
// remove verification flag for this node
|
|
|
|
verified_mask.clear(curr_verifying_node);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
last_verification_request = now;
|
|
|
|
//Find the next registered Node ID to be verified.
|
|
|
|
for (uint8_t i = 0; i <= MAX_NODE_ID; i++) {
|
|
|
|
curr_verifying_node = (curr_verifying_node + 1) % (MAX_NODE_ID + 1);
|
2023-01-04 21:09:23 -04:00
|
|
|
if ((curr_verifying_node == self_node_id) || (curr_verifying_node == 0)) {
|
|
|
|
continue;
|
|
|
|
}
|
2019-09-21 00:16:06 -03:00
|
|
|
if (isNodeSeen(curr_verifying_node)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
if (isNodeIDOccupied(curr_verifying_node)) {
|
|
|
|
uavcan_protocol_GetNodeInfoRequest request;
|
|
|
|
node_info_client.request(curr_verifying_node, request);
|
2022-04-04 07:33:33 -03:00
|
|
|
nodeInfo_resp_rcvd = false;
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Handles Node Status Message, adds to the Seen Node list
|
|
|
|
Also starts the Service call for Node Info to complete the
|
|
|
|
Verification process. */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::handleNodeStatus(const CanardRxTransfer& transfer, const uavcan_protocol_NodeStatus& msg)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
2023-01-04 21:09:23 -04:00
|
|
|
if (transfer.source_node_id > MAX_NODE_ID || transfer.source_node_id == 0) {
|
2019-09-21 00:16:06 -03:00
|
|
|
return;
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
if ((msg.health != UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK ||
|
|
|
|
msg.mode != UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL) &&
|
2023-04-06 21:18:01 -03:00
|
|
|
!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
|
2022-04-29 08:47:51 -03:00
|
|
|
//if node is not healthy or operational, clear resp health mask, and set fault_node_id
|
2023-01-04 21:09:23 -04:00
|
|
|
fault_node_id = transfer.source_node_id;
|
2022-04-29 08:47:51 -03:00
|
|
|
server_state = NODE_STATUS_UNHEALTHY;
|
2023-01-04 21:09:23 -04:00
|
|
|
node_healthy_mask.clear(transfer.source_node_id);
|
2022-04-29 08:47:51 -03:00
|
|
|
} else {
|
2023-01-04 21:09:23 -04:00
|
|
|
node_healthy_mask.set(transfer.source_node_id);
|
2022-04-29 08:47:51 -03:00
|
|
|
if (node_healthy_mask == verified_mask) {
|
|
|
|
server_state = HEALTHY;
|
|
|
|
}
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
if (!isNodeIDVerified(transfer.source_node_id)) {
|
2019-09-21 00:16:06 -03:00
|
|
|
//immediately begin verification of the node_id
|
2023-01-04 21:09:23 -04:00
|
|
|
uavcan_protocol_GetNodeInfoRequest request;
|
|
|
|
node_info_client.request(transfer.source_node_id, request);
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
//Add node to seen list if not seen before
|
2023-01-04 21:09:23 -04:00
|
|
|
addToSeenNodeMask(transfer.source_node_id);
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/* Node Info message handler
|
|
|
|
Handle responses from GetNodeInfo Request. We verify the node info
|
|
|
|
against our records. Marks Verification mask if already recorded,
|
|
|
|
Or register if the node id is available and not recorded for the
|
|
|
|
received Unique ID */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoResponse& rsp)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
2023-01-04 21:09:23 -04:00
|
|
|
if (transfer.source_node_id > MAX_NODE_ID) {
|
2019-09-21 00:16:06 -03:00
|
|
|
return;
|
|
|
|
}
|
2020-12-31 17:04:08 -04:00
|
|
|
/*
|
|
|
|
if we haven't logged this node then log it now
|
|
|
|
*/
|
2023-07-13 21:58:05 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2023-01-04 21:09:23 -04:00
|
|
|
if (!logged.get(transfer.source_node_id) && AP::logger().logging_started()) {
|
|
|
|
logged.set(transfer.source_node_id);
|
2020-12-31 17:04:08 -04:00
|
|
|
uint64_t uid[2];
|
2023-01-04 21:09:23 -04:00
|
|
|
memcpy(uid, rsp.hardware_version.unique_id, sizeof(rsp.hardware_version.unique_id));
|
2022-02-12 09:52:09 -04:00
|
|
|
// @LoggerMessage: CAND
|
|
|
|
// @Description: Info from GetNodeInfo request
|
|
|
|
// @Field: TimeUS: Time since system startup
|
2024-02-14 13:04:59 -04:00
|
|
|
// @Field: Driver: Driver index
|
2022-02-12 09:52:09 -04:00
|
|
|
// @Field: NodeId: Node ID
|
|
|
|
// @Field: UID1: Hardware ID, part 1
|
|
|
|
// @Field: UID2: Hardware ID, part 2
|
|
|
|
// @Field: Name: Name string
|
|
|
|
// @Field: Major: major revision id
|
|
|
|
// @Field: Minor: minor revision id
|
|
|
|
// @Field: Version: AP_Periph git hash
|
2024-02-14 13:04:59 -04:00
|
|
|
AP::logger().Write("CAND", "TimeUS,Driver,NodeId,UID1,UID2,Name,Major,Minor,Version",
|
|
|
|
"s-#------", "F--------", "QBBQQZBBI",
|
2020-12-31 17:04:08 -04:00
|
|
|
AP_HAL::micros64(),
|
2024-02-14 13:04:59 -04:00
|
|
|
_ap_dronecan.get_driver_index(),
|
2023-01-04 21:09:23 -04:00
|
|
|
transfer.source_node_id,
|
2020-12-31 17:04:08 -04:00
|
|
|
uid[0], uid[1],
|
2023-01-04 21:09:23 -04:00
|
|
|
rsp.name.data,
|
|
|
|
rsp.software_version.major,
|
|
|
|
rsp.software_version.minor,
|
|
|
|
rsp.software_version.vcs_commit);
|
2020-12-31 17:04:08 -04:00
|
|
|
}
|
2023-07-13 21:58:05 -03:00
|
|
|
#endif
|
2020-12-31 17:04:08 -04:00
|
|
|
|
2023-01-04 21:09:23 -04:00
|
|
|
if (isNodeIDOccupied(transfer.source_node_id)) {
|
2019-09-21 00:16:06 -03:00
|
|
|
//if node_id already registered, just verify if Unique ID matches as well
|
2023-01-04 21:09:23 -04:00
|
|
|
if (transfer.source_node_id == getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16)) {
|
|
|
|
if (transfer.source_node_id == curr_verifying_node) {
|
2019-09-21 00:16:06 -03:00
|
|
|
nodeInfo_resp_rcvd = true;
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
setVerificationMask(transfer.source_node_id);
|
2023-04-06 21:18:01 -03:00
|
|
|
} else if (!_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {
|
2019-09-21 00:16:06 -03:00
|
|
|
/* This is a device with node_id already registered
|
|
|
|
for another device */
|
|
|
|
server_state = DUPLICATE_NODES;
|
2023-01-04 21:09:23 -04:00
|
|
|
fault_node_id = transfer.source_node_id;
|
|
|
|
memcpy(fault_node_name, rsp.name.data, sizeof(fault_node_name));
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
/* Node Id was not allocated by us, or during this boot, let's register this in our records
|
|
|
|
Check if we allocated this Node before */
|
2023-01-04 21:09:23 -04:00
|
|
|
uint8_t prev_node_id = getNodeIDForUniqueID(rsp.hardware_version.unique_id, 16);
|
2019-09-21 00:16:06 -03:00
|
|
|
if (prev_node_id != 255) {
|
|
|
|
//yes we did, remove this registration
|
|
|
|
freeNodeID(prev_node_id);
|
|
|
|
}
|
|
|
|
//add a new server record
|
2023-01-04 21:09:23 -04:00
|
|
|
addNodeIDForUniqueID(transfer.source_node_id, rsp.hardware_version.unique_id, 16);
|
2019-09-21 00:16:06 -03:00
|
|
|
//Verify as well
|
2023-01-04 21:09:23 -04:00
|
|
|
setVerificationMask(transfer.source_node_id);
|
|
|
|
if (transfer.source_node_id == curr_verifying_node) {
|
2019-09-21 00:16:06 -03:00
|
|
|
nodeInfo_resp_rcvd = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Handle the allocation message from the devices supporting
|
|
|
|
dynamic node allocation. */
|
2023-04-06 21:18:01 -03:00
|
|
|
void AP_DroneCAN_DNA_Server::handleAllocation(const CanardRxTransfer& transfer, const uavcan_protocol_dynamic_node_id_Allocation& msg)
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
2023-01-04 21:09:23 -04:00
|
|
|
if (transfer.source_node_id != 0) {
|
2019-09-21 00:16:06 -03:00
|
|
|
//Ignore Allocation messages that are not DNA requests
|
|
|
|
return;
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2020-05-31 09:47:45 -03:00
|
|
|
if (rcvd_unique_id_offset == 0 ||
|
|
|
|
(now - last_alloc_msg_ms) > 500) {
|
2023-01-04 21:09:23 -04:00
|
|
|
if (msg.first_part_of_unique_id) {
|
2020-05-31 09:47:45 -03:00
|
|
|
rcvd_unique_id_offset = 0;
|
|
|
|
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
|
|
|
|
} else {
|
|
|
|
//we are only accepting first part
|
|
|
|
return;
|
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
} else if (msg.first_part_of_unique_id) {
|
2020-05-31 09:47:45 -03:00
|
|
|
// we are only accepting follow up messages
|
2019-09-21 00:16:06 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2020-05-31 09:47:45 -03:00
|
|
|
if (rcvd_unique_id_offset) {
|
2023-04-08 01:27:51 -03:00
|
|
|
debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting Followup part! %u\n",
|
2023-01-04 21:09:23 -04:00
|
|
|
(long int)AP_HAL::millis(),
|
2021-08-03 23:44:31 -03:00
|
|
|
unsigned((now - last_alloc_msg_ms)));
|
2020-05-31 09:47:45 -03:00
|
|
|
} else {
|
2023-04-08 01:27:51 -03:00
|
|
|
debug_dronecan(AP_CANManager::LOG_DEBUG, "TIME: %ld -- Accepting First part! %u\n",
|
2023-01-04 21:09:23 -04:00
|
|
|
(long int)AP_HAL::millis(),
|
2021-08-03 23:44:31 -03:00
|
|
|
unsigned((now - last_alloc_msg_ms)));
|
2020-05-31 09:47:45 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
last_alloc_msg_ms = now;
|
2023-01-04 21:09:23 -04:00
|
|
|
if ((rcvd_unique_id_offset + msg.unique_id.len) > 16) {
|
2019-09-21 00:16:06 -03:00
|
|
|
//This request is malformed, Reset!
|
|
|
|
rcvd_unique_id_offset = 0;
|
|
|
|
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
//copy over the unique_id
|
2023-01-04 21:09:23 -04:00
|
|
|
for (uint8_t i=rcvd_unique_id_offset; i<(rcvd_unique_id_offset + msg.unique_id.len); i++) {
|
|
|
|
rcvd_unique_id[i] = msg.unique_id.data[i - rcvd_unique_id_offset];
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
2023-01-04 21:09:23 -04:00
|
|
|
rcvd_unique_id_offset += msg.unique_id.len;
|
2019-09-21 00:16:06 -03:00
|
|
|
|
|
|
|
//send follow up message
|
2023-04-07 04:43:08 -03:00
|
|
|
uavcan_protocol_dynamic_node_id_Allocation rsp {};
|
2019-09-21 00:16:06 -03:00
|
|
|
|
2020-05-31 09:47:45 -03:00
|
|
|
/* Respond with the message containing the received unique ID so far
|
|
|
|
or with node id if we successfully allocated one. */
|
2023-01-04 21:09:23 -04:00
|
|
|
memcpy(rsp.unique_id.data, rcvd_unique_id, rcvd_unique_id_offset);
|
|
|
|
rsp.unique_id.len = rcvd_unique_id_offset;
|
2020-05-31 09:47:45 -03:00
|
|
|
|
2019-09-21 00:16:06 -03:00
|
|
|
if (rcvd_unique_id_offset == 16) {
|
|
|
|
//We have received the full Unique ID, time to do allocation
|
|
|
|
uint8_t resp_node_id = getNodeIDForUniqueID((const uint8_t*)rcvd_unique_id, 16);
|
|
|
|
if (resp_node_id == 255) {
|
2023-01-04 21:09:23 -04:00
|
|
|
resp_node_id = findFreeNodeID(msg.node_id);
|
2019-09-21 00:16:06 -03:00
|
|
|
if (resp_node_id != 255) {
|
|
|
|
if (addNodeIDForUniqueID(resp_node_id, (const uint8_t*)rcvd_unique_id, 16)) {
|
2023-01-04 21:09:23 -04:00
|
|
|
rsp.node_id = resp_node_id;
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
} else {
|
2020-11-05 19:35:00 -04:00
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UC Node Alloc Failed!");
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
} else {
|
2023-01-04 21:09:23 -04:00
|
|
|
rsp.node_id = resp_node_id;
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
2020-05-31 09:47:45 -03:00
|
|
|
//reset states as well
|
|
|
|
rcvd_unique_id_offset = 0;
|
|
|
|
memset(rcvd_unique_id, 0, sizeof(rcvd_unique_id));
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
|
2023-01-04 21:09:23 -04:00
|
|
|
allocation_pub.broadcast(rsp, false); // never publish allocation message with CAN FD
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
//report the server state, along with failure message if any
|
2023-04-06 21:18:01 -03:00
|
|
|
bool AP_DroneCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) const
|
2019-09-21 00:16:06 -03:00
|
|
|
{
|
|
|
|
switch (server_state) {
|
2020-05-01 02:20:00 -03:00
|
|
|
case HEALTHY:
|
|
|
|
return true;
|
2019-09-21 00:16:06 -03:00
|
|
|
case STORAGE_FAILURE: {
|
2020-05-01 02:20:00 -03:00
|
|
|
snprintf(fail_msg, fail_msg_len, "Failed to access storage!");
|
2019-09-21 00:16:06 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
case DUPLICATE_NODES: {
|
2023-04-06 21:18:01 -03:00
|
|
|
if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_DUPLICATE_NODE)) {
|
2021-09-10 23:47:02 -03:00
|
|
|
// ignore error
|
|
|
|
return true;
|
|
|
|
}
|
2020-05-01 02:20:00 -03:00
|
|
|
snprintf(fail_msg, fail_msg_len, "Duplicate Node %s../%d!", fault_node_name, fault_node_id);
|
2019-09-21 00:16:06 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
case FAILED_TO_ADD_NODE: {
|
2020-05-01 02:20:00 -03:00
|
|
|
snprintf(fail_msg, fail_msg_len, "Failed to add Node %d!", fault_node_id);
|
2019-09-21 00:16:06 -03:00
|
|
|
return false;
|
|
|
|
}
|
2022-04-29 08:47:51 -03:00
|
|
|
case NODE_STATUS_UNHEALTHY: {
|
2023-04-06 21:18:01 -03:00
|
|
|
if (_ap_dronecan.option_is_set(AP_DroneCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
|
2022-07-25 00:30:50 -03:00
|
|
|
// ignore error
|
|
|
|
return true;
|
|
|
|
}
|
2022-04-29 08:47:51 -03:00
|
|
|
snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id);
|
|
|
|
return false;
|
|
|
|
}
|
2019-09-21 00:16:06 -03:00
|
|
|
}
|
2020-05-01 02:20:00 -03:00
|
|
|
// should never get; compiler should enforce all server_states are covered
|
2019-09-21 00:16:06 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-06-24 09:07:28 -03:00
|
|
|
#endif //HAL_NUM_CAN_IFACES
|