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_CANManager/AP_CANManager.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15* AP_CANManager - board specific configuration for CAN interface16*/1718#include <AP_HAL/AP_HAL.h>19#include <AP_Common/AP_Common.h>20#include "AP_CANManager.h"2122#if HAL_CANMANAGER_ENABLED2324#include <AP_BoardConfig/AP_BoardConfig.h>25#include <AP_Vehicle/AP_Vehicle_Type.h>26#include <AP_DroneCAN/AP_DroneCAN.h>27#include <AP_KDECAN/AP_KDECAN.h>28#include <AP_SerialManager/AP_SerialManager.h>29#include <AP_PiccoloCAN/AP_PiccoloCAN.h>30#include <AP_EFI/AP_EFI_NWPMU.h>31#include <GCS_MAVLink/GCS.h>32#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX33#include <AP_HAL_Linux/CANSocketIface.h>34#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL35#include <AP_HAL_SITL/CANSocketIface.h>36#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS37#include <hal.h>38#include <AP_HAL_ChibiOS/CANIface.h>39#endif4041#include <AP_Common/ExpandingString.h>42#include <AP_Common/sorting.h>43#include <AP_Logger/AP_Logger.h>4445#define LOG_TAG "CANMGR"46#define LOG_BUFFER_SIZE 10244748extern const AP_HAL::HAL& hal;4950// table of user settable parameters51const AP_Param::GroupInfo AP_CANManager::var_info[] = {5253#if HAL_NUM_CAN_IFACES > 054// @Group: P1_55// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp56AP_SUBGROUPINFO(_interfaces[0], "P1_", 1, AP_CANManager, AP_CANManager::CANIface_Params),57#endif5859#if HAL_NUM_CAN_IFACES > 160// @Group: P2_61// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp62AP_SUBGROUPINFO(_interfaces[1], "P2_", 2, AP_CANManager, AP_CANManager::CANIface_Params),63#endif6465#if HAL_NUM_CAN_IFACES > 266// @Group: P3_67// @Path: ../AP_CANManager/AP_CANIfaceParams.cpp68AP_SUBGROUPINFO(_interfaces[2], "P3_", 3, AP_CANManager, AP_CANManager::CANIface_Params),69#endif7071#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 072// @Group: D1_73// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp74AP_SUBGROUPINFO(_drv_param[0], "D1_", 4, AP_CANManager, AP_CANManager::CANDriver_Params),75#endif7677#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 178// @Group: D2_79// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp80AP_SUBGROUPINFO(_drv_param[1], "D2_", 5, AP_CANManager, AP_CANManager::CANDriver_Params),81#endif8283#if HAL_MAX_CAN_PROTOCOL_DRIVERS > 284// @Group: D3_85// @Path: ../AP_CANManager/AP_CANManager_CANDriver_Params.cpp86AP_SUBGROUPINFO(_drv_param[2], "D3_", 6, AP_CANManager, AP_CANManager::CANDriver_Params),87#endif8889#if AP_CAN_SLCAN_ENABLED90// @Group: SLCAN_91// @Path: ../AP_CANManager/AP_SLCANIface.cpp92AP_SUBGROUPINFO(_slcan_interface, "SLCAN_", 7, AP_CANManager, SLCAN::CANIface),93#endif9495// @Param: LOGLEVEL96// @DisplayName: Loglevel97// @Description: Loglevel for recording initialisation and debug information from CAN Interface98// @Range: 0 499// @Values: 0: Log None, 1: Log Error, 2: Log Warning and below, 3: Log Info and below, 4: Log Everything100// @User: Advanced101AP_GROUPINFO("LOGLEVEL", 8, AP_CANManager, _loglevel, AP_CANManager::LOG_NONE),102103AP_GROUPEND104};105106AP_CANManager *AP_CANManager::_singleton;107108AP_CANManager::AP_CANManager()109{110AP_Param::setup_object_defaults(this, var_info);111if (_singleton != nullptr) {112AP_HAL::panic("AP_CANManager must be singleton");113}114_singleton = this;115}116117#if !AP_TEST_DRONECAN_DRIVERS118void AP_CANManager::init()119{120WITH_SEMAPHORE(_sem);121122// we need to mutate the HAL to install new CAN interfaces123AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();124125#if CONFIG_HAL_BOARD == HAL_BOARD_SITL126if (AP::sitl() == nullptr) {127AP_HAL::panic("CANManager: SITL not initialised!");128}129#endif130// We only allocate log buffer only when under debug131if (_loglevel != AP_CANManager::LOG_NONE) {132_log_buf = NEW_NOTHROW char[LOG_BUFFER_SIZE];133_log_pos = 0;134}135136#if AP_CAN_SLCAN_ENABLED137//Reset all SLCAN related params that needs resetting at boot138_slcan_interface.reset_params();139#endif140141AP_CAN::Protocol drv_type[HAL_MAX_CAN_PROTOCOL_DRIVERS] = {};142// loop through interfaces and allocate and initialise Iface,143// Also allocate Driver objects, and add interfaces to them144for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {145// Get associated Driver to the interface146uint8_t drv_num = _interfaces[i]._driver_number;147if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {148continue;149}150drv_num--;151152if (hal_mutable.can[i] == nullptr) {153// So if this interface is not allocated allocate it here,154// also pass the index of the CANBus155hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);156}157158// Initialise the interface we just allocated159if (hal_mutable.can[i] == nullptr) {160continue;161}162AP_HAL::CANIface* iface = hal_mutable.can[i];163164// Find the driver type that we need to allocate and register this interface with165drv_type[drv_num] = (AP_CAN::Protocol) _drv_param[drv_num]._driver_type.get();166bool can_initialised = false;167// Check if this interface need hooking up to slcan passthrough168// instead of a driver169#if AP_CAN_SLCAN_ENABLED170if (_slcan_interface.init_passthrough(i)) {171// we have slcan bridge setup pass that on as can iface172can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);173iface = &_slcan_interface;174} else {175#else176if (true) {177#endif178can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode);179}180181if (!can_initialised) {182log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "Failed to initialise CAN Interface %d", i+1);183continue;184}185186log_text(AP_CANManager::LOG_INFO, LOG_TAG, "CAN Interface %d initialized well", i + 1);187188if (_drivers[drv_num] != nullptr) {189//We already initialised the driver just add interface and move on190log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);191_drivers[drv_num]->add_interface(iface);192continue;193}194195if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {196// We are exceeding number of drivers,197// this can't be happening time to panic198AP_BoardConfig::config_error("Max number of CAN Drivers exceeded\n\r");199}200201// Allocate the set type of Driver202switch (drv_type[drv_num]) {203#if HAL_ENABLE_DRONECAN_DRIVERS204case AP_CAN::Protocol::DroneCAN:205_drivers[drv_num] = _drv_param[drv_num]._uavcan = NEW_NOTHROW AP_DroneCAN(drv_num);206207if (_drivers[drv_num] == nullptr) {208AP_BoardConfig::allocation_error("uavcan %d", i + 1);209continue;210}211212AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[drv_num], AP_DroneCAN::var_info);213break;214#endif215#if HAL_PICCOLO_CAN_ENABLE216case AP_CAN::Protocol::PiccoloCAN:217_drivers[drv_num] = _drv_param[drv_num]._piccolocan = NEW_NOTHROW AP_PiccoloCAN;218219if (_drivers[drv_num] == nullptr) {220AP_BoardConfig::allocation_error("PiccoloCAN %d", drv_num + 1);221continue;222}223224AP_Param::load_object_from_eeprom((AP_PiccoloCAN*)_drivers[drv_num], AP_PiccoloCAN::var_info);225break;226#endif227default:228continue;229}230231_num_drivers++;232233// Hook this interface to the selected Driver Type234_drivers[drv_num]->add_interface(iface);235log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);236237}238239for (uint8_t drv_num = 0; drv_num < HAL_MAX_CAN_PROTOCOL_DRIVERS; drv_num++) {240//initialise all the Drivers241242// Cache the driver type, initialized or not, so we can detect that it is in the params at boot via get_driver_type().243// This allows drivers that are initialized by CANSensor instead of CANManager to know if they should init or not244_driver_type_cache[drv_num] = drv_type[drv_num];245246if (_drivers[drv_num] == nullptr) {247continue;248}249bool enable_filter = false;250for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {251if (_interfaces[i]._driver_number == (drv_num+1) &&252hal_mutable.can[i] != nullptr &&253hal_mutable.can[i]->get_operating_mode() == AP_HAL::CANIface::FilteredMode) {254// Don't worry we don't enable Filters for Normal Ifaces under the driver255// this is just to ensure we enable them for the ones we already decided on256enable_filter = true;257break;258}259}260261_drivers[drv_num]->init(drv_num, enable_filter);262}263264#if AP_CAN_LOGGING_ENABLED265hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::check_logging_enable, void));266#endif267}268#else269void AP_CANManager::init()270{271WITH_SEMAPHORE(_sem);272for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {273if ((AP_CAN::Protocol) _drv_param[i]._driver_type.get() == AP_CAN::Protocol::DroneCAN) {274_drivers[i] = _drv_param[i]._uavcan = NEW_NOTHROW AP_DroneCAN(i);275276if (_drivers[i] == nullptr) {277AP_BoardConfig::allocation_error("uavcan %d", i + 1);278continue;279}280281AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info);282_drivers[i]->init(i, true);283_driver_type_cache[i] = (AP_CAN::Protocol) _drv_param[i]._driver_type.get();284}285}286}287#endif288289/*290register a new CAN driver291*/292bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver)293{294WITH_SEMAPHORE(_sem);295296// we need to mutate the HAL to install new CAN interfaces297AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();298299for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {300uint8_t drv_num = _interfaces[i]._driver_number;301if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {302continue;303}304// from 1 based to 0 based305drv_num--;306307if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type.get()) {308continue;309}310if (_drivers[drv_num] != nullptr) {311continue;312}313if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {314continue;315}316317if (hal_mutable.can[i] == nullptr) {318// if this interface is not allocated allocate it here,319// also pass the index of the CANBus320hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);321}322323// Initialise the interface we just allocated324if (hal_mutable.can[i] == nullptr) {325continue;326}327AP_HAL::CANIface* iface = hal_mutable.can[i];328329_drivers[drv_num] = driver;330_drivers[drv_num]->add_interface(iface);331log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);332333_drivers[drv_num]->init(drv_num, false);334_driver_type_cache[drv_num] = dtype;335336_num_drivers++;337338return true;339}340return false;341}342343// register a new auxillary sensor driver for 11 bit address frames344bool AP_CANManager::register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index)345{346WITH_SEMAPHORE(_sem);347348for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {349uint8_t drv_num = _interfaces[i]._driver_number;350if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {351continue;352}353// from 1 based to 0 based354drv_num--;355356if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type_11bit.get()) {357continue;358}359if (_drivers[drv_num] != nullptr &&360_drivers[drv_num]->add_11bit_driver(sensor)) {361driver_index = drv_num;362return true;363}364}365return false;366367}368369// Method used by CAN related library methods to report status and debug info370// The result of this method can be accessed via ftp get @SYS/can_log.txt371void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...)372{373if (_log_buf == nullptr) {374return;375}376if (loglevel > _loglevel) {377return;378}379WITH_SEMAPHORE(_sem);380381if ((LOG_BUFFER_SIZE - _log_pos) < (10 + strlen(tag) + strlen(fmt))) {382// reset log pos383_log_pos = 0;384}385//Tag Log Message386const char *log_level_tag = "";387switch (loglevel) {388case AP_CANManager::LOG_DEBUG :389log_level_tag = "DEBUG";390break;391392case AP_CANManager::LOG_INFO :393log_level_tag = "INFO";394break;395396case AP_CANManager::LOG_WARNING :397log_level_tag = "WARN";398break;399400case AP_CANManager::LOG_ERROR :401log_level_tag = "ERROR";402break;403404case AP_CANManager::LOG_NONE:405return;406}407408_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s %s :", log_level_tag, tag);409410va_list arg_list;411va_start(arg_list, fmt);412_log_pos += hal.util->vsnprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, fmt, arg_list);413va_end(arg_list);414}415416// log retrieve method used by file sys method to report can log417void AP_CANManager::log_retrieve(ExpandingString &str) const418{419if (_log_buf == nullptr) {420GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Log buffer not available");421return;422}423str.append(_log_buf, _log_pos);424}425426#if HAL_GCS_ENABLED427/*428handle MAV_CMD_CAN_FORWARD mavlink long command429*/430bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)431{432WITH_SEMAPHORE(can_forward.sem);433const int8_t bus = int8_t(packet.param1)-1;434435if (bus == -1) {436/*437a request to stop forwarding438*/439if (can_forward.callback_id != 0) {440hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);441can_forward.callback_id = 0;442}443return true;444}445446if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {447return false;448}449450if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) {451/*452the client is changing which bus they are monitoring, unregister from the previous bus453*/454hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);455can_forward.callback_id = 0;456}457458if (can_forward.callback_id == 0 &&459!hal.can[bus]->register_frame_callback(460FUNCTOR_BIND_MEMBER(&AP_CANManager::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &), can_forward.callback_id)) {461// failed to register the callback462return false;463}464465can_forward.callback_bus = bus;466can_forward.last_callback_enable_ms = AP_HAL::millis();467can_forward.chan = chan;468can_forward.system_id = msg.sysid;469can_forward.component_id = msg.compid;470471return true;472}473474/*475handle a CAN_FRAME packet476*/477void AP_CANManager::handle_can_frame(const mavlink_message_t &msg)478{479if (frame_buffer == nullptr) {480// allocate frame buffer481WITH_SEMAPHORE(_sem);482// 20 is good for firmware upload483uint8_t buffer_size = 20;484while (frame_buffer == nullptr && buffer_size > 0) {485// we'd like 20 frames, but will live with less486frame_buffer = NEW_NOTHROW ObjectBuffer<BufferFrame>(buffer_size);487if (frame_buffer != nullptr && frame_buffer->get_size() != 0) {488// register a callback for when frames can't be sent immediately489hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::process_frame_buffer, void));490break;491}492delete frame_buffer;493frame_buffer = nullptr;494buffer_size /= 2;495}496if (frame_buffer == nullptr) {497// discard the frames498return;499}500}501502switch (msg.msgid) {503case MAVLINK_MSG_ID_CAN_FRAME: {504mavlink_can_frame_t p;505mavlink_msg_can_frame_decode(&msg, &p);506if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {507return;508}509struct BufferFrame frame {510bus : p.bus,511frame : AP_HAL::CANFrame(p.id, p.data, p.len)512};513WITH_SEMAPHORE(_sem);514frame_buffer->push(frame);515break;516}517#if HAL_CANFD_SUPPORTED518case MAVLINK_MSG_ID_CANFD_FRAME: {519mavlink_canfd_frame_t p;520mavlink_msg_canfd_frame_decode(&msg, &p);521if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {522return;523}524struct BufferFrame frame {525bus : p.bus,526frame : AP_HAL::CANFrame(p.id, p.data, p.len, true)527};528WITH_SEMAPHORE(_sem);529frame_buffer->push(frame);530break;531}532#endif533}534process_frame_buffer();535}536537/*538process the frame buffer539*/540void AP_CANManager::process_frame_buffer(void)541{542while (frame_buffer) {543WITH_SEMAPHORE(_sem);544struct BufferFrame frame;545const uint16_t timeout_us = 2000;546if (!frame_buffer->peek(frame)) {547// no frames in the queue548break;549}550const int16_t retcode = hal.can[frame.bus]->send(frame.frame,551AP_HAL::micros64() + timeout_us,552AP_HAL::CANIface::IsMAVCAN);553if (retcode == 0) {554// no space in the CAN output slots, try again later555break;556}557// retcode == 1 means sent, -1 means a frame that can't be558// sent. Either way we should remove from the queue559frame_buffer->pop();560}561}562563/*564handle a CAN_FILTER_MODIFY packet565*/566void AP_CANManager::handle_can_filter_modify(const mavlink_message_t &msg)567{568mavlink_can_filter_modify_t p;569mavlink_msg_can_filter_modify_decode(&msg, &p);570const int8_t bus = int8_t(p.bus)-1;571if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {572return;573}574if (p.num_ids > ARRAY_SIZE(p.ids)) {575return;576}577uint16_t *new_ids = nullptr;578uint16_t num_new_ids = 0;579WITH_SEMAPHORE(can_forward.sem);580581// sort the list, so we can bisection search and the array582// operations below are efficient583insertion_sort_uint16(p.ids, p.num_ids);584585switch (p.operation) {586case CAN_FILTER_REPLACE: {587if (p.num_ids == 0) {588can_forward.num_filter_ids = 0;589delete[] can_forward.filter_ids;590can_forward.filter_ids = nullptr;591return;592}593if (p.num_ids == can_forward.num_filter_ids &&594memcmp(p.ids, can_forward.filter_ids, p.num_ids*sizeof(uint16_t)) == 0) {595// common case of replacing with identical list596return;597}598new_ids = NEW_NOTHROW uint16_t[p.num_ids];599if (new_ids != nullptr) {600num_new_ids = p.num_ids;601memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t));602}603break;604}605case CAN_FILTER_ADD: {606if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,607p.ids, p.num_ids) == p.num_ids) {608// nothing changing609return;610}611new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids];612if (new_ids == nullptr) {613return;614}615if (can_forward.num_filter_ids != 0) {616memcpy(new_ids, can_forward.filter_ids, can_forward.num_filter_ids*sizeof(uint16_t));617}618memcpy(&new_ids[can_forward.num_filter_ids], p.ids, p.num_ids*sizeof(uint16_t));619insertion_sort_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);620num_new_ids = remove_duplicates_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);621break;622}623case CAN_FILTER_REMOVE: {624if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,625p.ids, p.num_ids) == 0) {626// nothing changing627return;628}629can_forward.num_filter_ids = remove_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,630p.ids, p.num_ids);631if (can_forward.num_filter_ids == 0) {632delete[] can_forward.filter_ids;633can_forward.filter_ids = nullptr;634}635break;636}637}638if (new_ids != nullptr) {639// handle common case of no change640if (num_new_ids == can_forward.num_filter_ids &&641memcmp(new_ids, can_forward.filter_ids, num_new_ids*sizeof(uint16_t)) == 0) {642delete[] new_ids;643} else {644// put the new list in place645delete[] can_forward.filter_ids;646can_forward.filter_ids = new_ids;647can_forward.num_filter_ids = num_new_ids;648}649}650}651652/*653handler for CAN frames from the registered callback, sending frames654out as CAN_FRAME or CANFD_FRAME messages655*/656void AP_CANManager::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame)657{658WITH_SEMAPHORE(can_forward.sem);659if (bus != can_forward.callback_bus) {660// we are not registered for forwarding this bus, discard frame661return;662}663if (can_forward.frame_counter++ == 100) {664// check every 100 frames for disabling CAN_FRAME send665// we stop sending after 5s if the client stops666// sending MAV_CMD_CAN_FORWARD requests667if (can_forward.callback_id != 0 &&668AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) {669hal.can[bus]->unregister_frame_callback(can_forward.callback_id);670can_forward.callback_id = 0;671return;672}673can_forward.frame_counter = 0;674}675WITH_SEMAPHORE(comm_chan_lock(can_forward.chan));676if (can_forward.filter_ids != nullptr) {677// work out ID of this frame678uint16_t id = 0;679if ((frame.id&0xff) != 0) {680// not anonymous681if (frame.id & 0x80) {682// service message683id = uint8_t(frame.id>>16);684} else {685// message frame686id = uint16_t(frame.id>>8);687}688}689if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) {690return;691}692}693const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc);694#if HAL_CANFD_SUPPORTED695if (frame.isCanFDFrame()) {696if (HAVE_PAYLOAD_SPACE(can_forward.chan, CANFD_FRAME)) {697mavlink_msg_canfd_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id,698bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));699}700} else701#endif702{703if (HAVE_PAYLOAD_SPACE(can_forward.chan, CAN_FRAME)) {704mavlink_msg_can_frame_send(can_forward.chan, can_forward.system_id, can_forward.component_id,705bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));706}707}708}709#endif // HAL_GCS_ENABLED710711#if AP_CAN_LOGGING_ENABLED712/*713handler for CAN frames for frame logging714*/715void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame)716{717#if HAL_CANFD_SUPPORTED718if (frame.canfd) {719struct log_CAFD pkt {720LOG_PACKET_HEADER_INIT(LOG_CAFD_MSG),721time_us : AP_HAL::micros64(),722bus : bus,723id : frame.id,724dlc : frame.dlc725};726memcpy(pkt.data, frame.data, frame.dlcToDataLength(frame.dlc));727AP::logger().WriteBlock(&pkt, sizeof(pkt));728return;729}730#endif731struct log_CANF pkt {732LOG_PACKET_HEADER_INIT(LOG_CANF_MSG),733time_us : AP_HAL::micros64(),734bus : bus,735id : frame.id,736dlc : frame.dlc737};738memcpy(pkt.data, frame.data, frame.dlc);739AP::logger().WriteBlock(&pkt, sizeof(pkt));740}741742/*743see if we need to enable/disable the CAN logging callback744*/745void AP_CANManager::check_logging_enable(void)746{747for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {748const bool enabled = _interfaces[i].option_is_set(CANIface_Params::Options::LOG_ALL_FRAMES);749uint8_t &logging_id = _interfaces[i].logging_id;750auto *can = hal.can[i];751if (can == nullptr) {752continue;753}754if (enabled && logging_id == 0) {755can->register_frame_callback(756FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &),757logging_id);758} else if (!enabled && logging_id != 0) {759can->unregister_frame_callback(logging_id);760}761}762}763764#endif // AP_CAN_LOGGING_ENABLED765766AP_CANManager& AP::can()767{768return *AP_CANManager::get_singleton();769}770771#endif772773774775