Path: blob/master/libraries/AP_CANManager/AP_CANManager.cpp
9317 views
/*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);173iface = &_slcan_interface;174} else {175#else176if (true) {177#endif178can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000);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 AP_PICCOLOCAN_ENABLED216case 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}249250_drivers[drv_num]->init(drv_num);251}252253#if AP_CAN_LOGGING_ENABLED254hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_CANManager::check_logging_enable, void));255#endif256}257#else258void AP_CANManager::init()259{260WITH_SEMAPHORE(_sem);261for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {262if ((AP_CAN::Protocol) _drv_param[i]._driver_type.get() == AP_CAN::Protocol::DroneCAN) {263_drivers[i] = _drv_param[i]._uavcan = NEW_NOTHROW AP_DroneCAN(i);264265if (_drivers[i] == nullptr) {266AP_BoardConfig::allocation_error("uavcan %d", i + 1);267continue;268}269270AP_Param::load_object_from_eeprom((AP_DroneCAN*)_drivers[i], AP_DroneCAN::var_info);271_drivers[i]->init(i);272_driver_type_cache[i] = (AP_CAN::Protocol) _drv_param[i]._driver_type.get();273}274}275}276#endif277278/*279register a new CAN driver280*/281bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver)282{283WITH_SEMAPHORE(_sem);284285// we need to mutate the HAL to install new CAN interfaces286AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable();287288for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {289uint8_t drv_num = _interfaces[i]._driver_number;290if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {291continue;292}293// from 1 based to 0 based294drv_num--;295296if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type.get()) {297continue;298}299if (_drivers[drv_num] != nullptr) {300continue;301}302if (_num_drivers >= HAL_MAX_CAN_PROTOCOL_DRIVERS) {303continue;304}305306if (hal_mutable.can[i] == nullptr) {307// if this interface is not allocated allocate it here,308// also pass the index of the CANBus309hal_mutable.can[i] = NEW_NOTHROW HAL_CANIface(i);310}311312// Initialise the interface we just allocated313if (hal_mutable.can[i] == nullptr) {314continue;315}316AP_HAL::CANIface* iface = hal_mutable.can[i];317318_drivers[drv_num] = driver;319_drivers[drv_num]->add_interface(iface);320log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Adding Interface %d to Driver %d", i + 1, drv_num + 1);321322_drivers[drv_num]->init(drv_num);323_driver_type_cache[drv_num] = dtype;324325_num_drivers++;326327return true;328}329return false;330}331332// register a new auxillary sensor driver for 11 bit address frames333bool AP_CANManager::register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index)334{335WITH_SEMAPHORE(_sem);336337for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {338uint8_t drv_num = _interfaces[i]._driver_number;339if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) {340continue;341}342// from 1 based to 0 based343drv_num--;344345if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type_11bit.get()) {346continue;347}348if (_drivers[drv_num] != nullptr &&349_drivers[drv_num]->add_11bit_driver(sensor)) {350driver_index = drv_num;351return true;352}353}354return false;355356}357358// Method used by CAN related library methods to report status and debug info359// The result of this method can be accessed via ftp get @SYS/can_log.txt360void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...)361{362if (_log_buf == nullptr) {363return;364}365if (loglevel > _loglevel) {366return;367}368WITH_SEMAPHORE(_sem);369370if ((LOG_BUFFER_SIZE - _log_pos) < (10 + strlen(tag) + strlen(fmt))) {371// reset log pos372_log_pos = 0;373}374//Tag Log Message375const char *log_level_tag = "";376switch (loglevel) {377case AP_CANManager::LOG_DEBUG :378log_level_tag = "DEBUG";379break;380381case AP_CANManager::LOG_INFO :382log_level_tag = "INFO";383break;384385case AP_CANManager::LOG_WARNING :386log_level_tag = "WARN";387break;388389case AP_CANManager::LOG_ERROR :390log_level_tag = "ERROR";391break;392393case AP_CANManager::LOG_NONE:394return;395}396397_log_pos += hal.util->snprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, "\n%s %s :", log_level_tag, tag);398399va_list arg_list;400va_start(arg_list, fmt);401_log_pos += hal.util->vsnprintf(&_log_buf[_log_pos], LOG_BUFFER_SIZE - _log_pos, fmt, arg_list);402va_end(arg_list);403}404405// log retrieve method used by file sys method to report can log406void AP_CANManager::log_retrieve(ExpandingString &str) const407{408if (_log_buf == nullptr) {409GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Log buffer not available");410return;411}412str.append(_log_buf, _log_pos);413}414415#if AP_CAN_LOGGING_ENABLED416/*417handler for CAN frames for frame logging418*/419void AP_CANManager::can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)420{421#if HAL_CANFD_SUPPORTED422if (frame.canfd) {423struct log_CAFD pkt {424LOG_PACKET_HEADER_INIT(LOG_CAFD_MSG),425time_us : AP_HAL::micros64(),426bus : bus,427id : frame.id,428dlc : frame.dlc429};430memcpy(pkt.data, frame.data, frame.dlcToDataLength(frame.dlc));431AP::logger().WriteBlock(&pkt, sizeof(pkt));432return;433}434#endif435struct log_CANF pkt {436LOG_PACKET_HEADER_INIT(LOG_CANF_MSG),437time_us : AP_HAL::micros64(),438bus : bus,439id : frame.id,440dlc : frame.dlc441};442memcpy(pkt.data, frame.data, frame.dlc);443AP::logger().WriteBlock(&pkt, sizeof(pkt));444}445446/*447see if we need to enable/disable the CAN logging callback448*/449void AP_CANManager::check_logging_enable(void)450{451for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) {452const bool enabled = _interfaces[i].option_is_set(CANIface_Params::Options::LOG_ALL_FRAMES);453uint8_t &logging_id = _interfaces[i].logging_id;454auto *can = hal.can[i];455if (can == nullptr) {456continue;457}458if (enabled && logging_id == 0) {459can->register_frame_callback(460FUNCTOR_BIND_MEMBER(&AP_CANManager::can_logging_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags),461logging_id);462} else if (!enabled && logging_id != 0) {463can->unregister_frame_callback(logging_id);464}465}466}467468#endif // AP_CAN_LOGGING_ENABLED469470AP_CANManager& AP::can()471{472return *AP_CANManager::get_singleton();473}474475#endif476477478479