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_Canard_iface.cpp
Views: 1798
#include "AP_Canard_iface.h"1#include <AP_HAL/AP_HAL.h>2#include <AP_CANManager/AP_CANManager.h>3#if HAL_ENABLE_DRONECAN_DRIVERS4#include <canard/handler_list.h>5#include <canard/transfer_object.h>6#include <AP_Math/AP_Math.h>7#include <dronecan_msgs.h>8extern const AP_HAL::HAL& hal;9#define LOG_TAG "DroneCANIface"10#include <canard.h>11#include <AP_CANManager/AP_CANSensor.h>1213#define DEBUG_PKTS 01415#define CANARD_MSG_TYPE_FROM_ID(x) ((uint16_t)(((x) >> 8U) & 0xFFFFU))1617DEFINE_HANDLER_LIST_HEADS();18DEFINE_HANDLER_LIST_SEMAPHORES();1920DEFINE_TRANSFER_OBJECT_HEADS();21DEFINE_TRANSFER_OBJECT_SEMAPHORES();2223#if AP_TEST_DRONECAN_DRIVERS24CanardInterface* CanardInterface::canard_ifaces[] = {nullptr, nullptr, nullptr};25CanardInterface CanardInterface::test_iface{2};26uint8_t test_node_mem_area[1024];27HAL_Semaphore test_iface_sem;28#endif2930void canard_allocate_sem_take(CanardPoolAllocator *allocator) {31if (allocator->semaphore == nullptr) {32allocator->semaphore = NEW_NOTHROW HAL_Semaphore;33if (allocator->semaphore == nullptr) {34// out of memory35CANARD_ASSERT(0);36return;37}38}39((HAL_Semaphore*)allocator->semaphore)->take_blocking();40}4142void canard_allocate_sem_give(CanardPoolAllocator *allocator) {43if (allocator->semaphore == nullptr) {44// it should have been allocated by canard_allocate_sem_take45CANARD_ASSERT(0);46return;47}48((HAL_Semaphore*)allocator->semaphore)->give();49}5051CanardInterface::CanardInterface(uint8_t iface_index) :52Interface(iface_index) {53#if AP_TEST_DRONECAN_DRIVERS54if (iface_index < 3) {55canard_ifaces[iface_index] = this;56}57if (iface_index == 0) {58test_iface.init(test_node_mem_area, sizeof(test_node_mem_area), 125);59}60canardInitTxTransfer(&tx_transfer);61#endif62}6364void CanardInterface::init(void* mem_arena, size_t mem_arena_size, uint8_t node_id) {65canardInit(&canard, mem_arena, mem_arena_size, onTransferReception, shouldAcceptTransfer, this);66canardSetLocalNodeID(&canard, node_id);67initialized = true;68}6970bool CanardInterface::broadcast(const Canard::Transfer &bcast_transfer) {71if (!initialized) {72return false;73}74WITH_SEMAPHORE(_sem_tx);7576#if AP_TEST_DRONECAN_DRIVERS77if (this == &test_iface) {78test_iface_sem.take_blocking();79}80#endif8182tx_transfer = {83.transfer_type = bcast_transfer.transfer_type,84.data_type_signature = bcast_transfer.data_type_signature,85.data_type_id = bcast_transfer.data_type_id,86.inout_transfer_id = bcast_transfer.inout_transfer_id,87.priority = bcast_transfer.priority,88.payload = (const uint8_t*)bcast_transfer.payload,89.payload_len = uint16_t(bcast_transfer.payload_len),90#if CANARD_ENABLE_CANFD91.canfd = bcast_transfer.canfd,92#endif93.deadline_usec = AP_HAL::micros64() + (bcast_transfer.timeout_ms * 1000),94#if CANARD_MULTI_IFACE95.iface_mask = uint8_t((1<<num_ifaces) - 1),96#endif97};98// do canard broadcast99int16_t ret = canardBroadcastObj(&canard, &tx_transfer);100#if AP_TEST_DRONECAN_DRIVERS101if (this == &test_iface) {102test_iface_sem.give();103}104#endif105if (ret <= 0) {106protocol_stats.tx_errors++;107} else {108protocol_stats.tx_frames += ret;109}110return ret > 0;111}112113bool CanardInterface::request(uint8_t destination_node_id, const Canard::Transfer &req_transfer) {114if (!initialized) {115return false;116}117WITH_SEMAPHORE(_sem_tx);118119tx_transfer = {120.transfer_type = req_transfer.transfer_type,121.data_type_signature = req_transfer.data_type_signature,122.data_type_id = req_transfer.data_type_id,123.inout_transfer_id = req_transfer.inout_transfer_id,124.priority = req_transfer.priority,125.payload = (const uint8_t*)req_transfer.payload,126.payload_len = uint16_t(req_transfer.payload_len),127#if CANARD_ENABLE_CANFD128.canfd = req_transfer.canfd,129#endif130.deadline_usec = AP_HAL::micros64() + (req_transfer.timeout_ms * 1000),131#if CANARD_MULTI_IFACE132.iface_mask = uint8_t((1<<num_ifaces) - 1),133#endif134};135// do canard request136int16_t ret = canardRequestOrRespondObj(&canard, destination_node_id, &tx_transfer);137if (ret <= 0) {138protocol_stats.tx_errors++;139} else {140protocol_stats.tx_frames += ret;141}142return ret > 0;143}144145bool CanardInterface::respond(uint8_t destination_node_id, const Canard::Transfer &res_transfer) {146if (!initialized) {147return false;148}149WITH_SEMAPHORE(_sem_tx);150151tx_transfer = {152.transfer_type = res_transfer.transfer_type,153.data_type_signature = res_transfer.data_type_signature,154.data_type_id = res_transfer.data_type_id,155.inout_transfer_id = res_transfer.inout_transfer_id,156.priority = res_transfer.priority,157.payload = (const uint8_t*)res_transfer.payload,158.payload_len = uint16_t(res_transfer.payload_len),159#if CANARD_ENABLE_CANFD160.canfd = res_transfer.canfd,161#endif162.deadline_usec = AP_HAL::micros64() + (res_transfer.timeout_ms * 1000),163#if CANARD_MULTI_IFACE164.iface_mask = uint8_t((1<<num_ifaces) - 1),165#endif166};167// do canard respond168int16_t ret = canardRequestOrRespondObj(&canard, destination_node_id, &tx_transfer);169if (ret <= 0) {170protocol_stats.tx_errors++;171} else {172protocol_stats.tx_frames += ret;173}174return ret > 0;175}176177void CanardInterface::onTransferReception(CanardInstance* ins, CanardRxTransfer* transfer) {178CanardInterface* iface = (CanardInterface*) ins->user_reference;179iface->handle_message(*transfer);180}181182bool CanardInterface::shouldAcceptTransfer(const CanardInstance* ins,183uint64_t* out_data_type_signature,184uint16_t data_type_id,185CanardTransferType transfer_type,186uint8_t source_node_id) {187CanardInterface* iface = (CanardInterface*) ins->user_reference;188return iface->accept_message(data_type_id, *out_data_type_signature);189}190191#if AP_TEST_DRONECAN_DRIVERS192void CanardInterface::processTestRx() {193if (!test_iface.initialized) {194return;195}196WITH_SEMAPHORE(test_iface_sem);197for (const CanardCANFrame* txf = canardPeekTxQueue(&test_iface.canard); txf != NULL; txf = canardPeekTxQueue(&test_iface.canard)) {198if (canard_ifaces[0]) {199canardHandleRxFrame(&canard_ifaces[0]->canard, txf, AP_HAL::micros64());200}201canardPopTxQueue(&test_iface.canard);202}203}204#endif205206void CanardInterface::processTx(bool raw_commands_only = false) {207WITH_SEMAPHORE(_sem_tx);208209for (uint8_t iface = 0; iface < num_ifaces; iface++) {210if (ifaces[iface] == NULL) {211continue;212}213auto txq = canard.tx_queue;214if (txq == nullptr) {215return;216}217// volatile as the value can change at any time during can interrupt218// we need to ensure that this is not optimized219volatile const auto *stats = ifaces[iface]->get_statistics();220uint64_t last_transmit_us = stats==nullptr?0:stats->last_transmit_us;221bool iface_down = true;222if (stats == nullptr || (AP_HAL::micros64() - last_transmit_us) < 200000UL) {223/*224We were not able to queue the frame for225sending. Only mark the send as failing if the226interface is active. We consider an interface as227active if it has had successful transmits for some time.228*/229iface_down = false;230}231// scan through list of pending transfers232while (true) {233auto txf = &txq->frame;234if (raw_commands_only &&235CANARD_MSG_TYPE_FROM_ID(txf->id) != UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID &&236CANARD_MSG_TYPE_FROM_ID(txf->id) != COM_HOBBYWING_ESC_RAWCOMMAND_ID) {237// look at next transfer238txq = txq->next;239if (txq == nullptr) {240break;241}242continue;243}244AP_HAL::CANFrame txmsg {};245txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);246memcpy(txmsg.data, txf->data, txf->data_len);247txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);248#if HAL_CANFD_SUPPORTED249txmsg.canfd = txf->canfd;250#endif251bool write = true;252bool read = false;253ifaces[iface]->select(read, write, &txmsg, 0);254if (!write) {255// if there is no space then we need to start from the256// top of the queue, so wait for the next loop257if (!iface_down) {258break;259} else {260txf->iface_mask &= ~(1U<<iface);261}262} else if ((txf->iface_mask & (1U<<iface)) && (AP_HAL::micros64() < txf->deadline_usec)) {263// try sending to interfaces, clearing the mask if we succeed264if (ifaces[iface]->send(txmsg, txf->deadline_usec, 0) > 0) {265txf->iface_mask &= ~(1U<<iface);266} else {267// if we fail to send then we try sending on next interface268if (!iface_down) {269break;270} else {271txf->iface_mask &= ~(1U<<iface);272}273}274}275// look at next transfer276txq = txq->next;277if (txq == nullptr) {278break;279}280}281}282283}284285void CanardInterface::update_rx_protocol_stats(int16_t res)286{287switch (res) {288case CANARD_OK:289protocol_stats.rx_frames++;290break;291case -CANARD_ERROR_OUT_OF_MEMORY:292protocol_stats.rx_error_oom++;293break;294case -CANARD_ERROR_INTERNAL:295protocol_stats.rx_error_internal++;296break;297case -CANARD_ERROR_RX_INCOMPATIBLE_PACKET:298protocol_stats.rx_ignored_not_wanted++;299break;300case -CANARD_ERROR_RX_WRONG_ADDRESS:301protocol_stats.rx_ignored_wrong_address++;302break;303case -CANARD_ERROR_RX_NOT_WANTED:304protocol_stats.rx_ignored_not_wanted++;305break;306case -CANARD_ERROR_RX_MISSED_START:307protocol_stats.rx_error_missed_start++;308break;309case -CANARD_ERROR_RX_WRONG_TOGGLE:310protocol_stats.rx_error_wrong_toggle++;311break;312case -CANARD_ERROR_RX_UNEXPECTED_TID:313protocol_stats.rx_ignored_unexpected_tid++;314break;315case -CANARD_ERROR_RX_SHORT_FRAME:316protocol_stats.rx_error_short_frame++;317break;318case -CANARD_ERROR_RX_BAD_CRC:319protocol_stats.rx_error_bad_crc++;320break;321default:322// mark all other errors as internal323protocol_stats.rx_error_internal++;324break;325}326}327328void CanardInterface::processRx() {329AP_HAL::CANFrame rxmsg;330for (uint8_t i=0; i<num_ifaces; i++) {331while(true) {332if (ifaces[i] == NULL) {333break;334}335bool read_select = true;336bool write_select = false;337ifaces[i]->select(read_select, write_select, nullptr, 0);338if (!read_select) { // No data pending339break;340}341CanardCANFrame rx_frame {};342343//palToggleLine(HAL_GPIO_PIN_LED);344uint64_t timestamp;345AP_HAL::CANIface::CanIOFlags flags;346if (ifaces[i]->receive(rxmsg, timestamp, flags) <= 0) {347break;348}349350if (!rxmsg.isExtended()) {351// 11 bit frame, see if we have a handler352if (aux_11bit_driver != nullptr) {353aux_11bit_driver->handle_frame(rxmsg);354}355continue;356}357358rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc);359memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);360#if HAL_CANFD_SUPPORTED361rx_frame.canfd = rxmsg.canfd;362#endif363rx_frame.id = rxmsg.id;364#if CANARD_MULTI_IFACE365rx_frame.iface_id = i;366#endif367{368WITH_SEMAPHORE(_sem_rx);369370const int16_t res = canardHandleRxFrame(&canard, &rx_frame, timestamp);371if (res == -CANARD_ERROR_RX_MISSED_START) {372// this might remaining frames from a message that we don't accept, so check373uint64_t dummy_signature;374if (shouldAcceptTransfer(&canard,375&dummy_signature,376extractDataType(rx_frame.id),377extractTransferType(rx_frame.id),3781)) { // doesn't matter what we pass here379update_rx_protocol_stats(res);380} else {381protocol_stats.rx_ignored_not_wanted++;382}383} else {384update_rx_protocol_stats(res);385}386}387}388}389}390391void CanardInterface::process(uint32_t duration_ms) {392#if AP_TEST_DRONECAN_DRIVERS393const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000;394while (AP_HAL::micros64() < deadline) {395processTestRx();396hal.scheduler->delay_microseconds(1000);397}398#else399const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000;400while (true) {401processRx();402processTx();403{404WITH_SEMAPHORE(_sem_rx);405WITH_SEMAPHORE(_sem_tx);406canardCleanupStaleTransfers(&canard, AP_HAL::micros64());407}408const uint64_t now = AP_HAL::micros64();409if (now < deadline) {410IGNORE_RETURN(sem_handle.wait(deadline - now));411} else {412break;413}414}415#endif416}417418bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface)419{420if (num_ifaces > HAL_NUM_CAN_IFACES) {421AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Num Ifaces Exceeded\n");422return false;423}424if (can_iface == nullptr) {425AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface Null\n");426return false;427}428if (ifaces[num_ifaces] != nullptr) {429AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Iface already added\n");430return false;431}432ifaces[num_ifaces] = can_iface;433if (ifaces[num_ifaces] == nullptr) {434AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Can't alloc uavcan::iface\n");435return false;436}437if (!can_iface->set_event_handle(&sem_handle)) {438AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Setting event handle failed\n");439return false;440}441AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "DroneCANIfaceMgr: Successfully added interface %d\n", int(num_ifaces));442num_ifaces++;443return true;444}445446// add an 11 bit auxillary driver447bool CanardInterface::add_11bit_driver(CANSensor *sensor)448{449if (aux_11bit_driver != nullptr) {450// only allow one451return false;452}453aux_11bit_driver = sensor;454return true;455}456457// handler for outgoing frames for auxillary drivers458bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)459{460const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us;461bool ret = false;462for (uint8_t iface = 0; iface < num_ifaces; iface++) {463if (ifaces[iface] == NULL) {464continue;465}466ret |= ifaces[iface]->send(out_frame, tx_deadline_us, 0) > 0;467}468return ret;469}470471#endif // #if HAL_ENABLE_DRONECAN_DRIVERS472473474