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/Tools/AP_Periph/can.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/*15AP_Periph can support16*/1718#include <AP_HAL/AP_HAL.h>19#include <AP_Math/AP_Math.h>20#include <AP_HAL/AP_HAL_Boards.h>21#include "AP_Periph.h"22#include <stdio.h>23#include <drivers/stm32/canard_stm32.h>24#include <AP_HAL/I2CDevice.h>25#include <AP_HAL/utility/RingBuffer.h>26#include <AP_Common/AP_FWVersion.h>27#include <dronecan_msgs.h>2829#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS30#include <hal.h>31#include <AP_HAL_ChibiOS/CANIface.h>32#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>33#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>34#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL35#include <AP_HAL_SITL/CANSocketIface.h>36#include <AP_HAL_SITL/AP_HAL_SITL.h>37#endif3839#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U)4041#include "i2c.h"42#include <utility>4344#if HAL_NUM_CAN_IFACES >= 245#include <AP_CANManager/AP_CANSensor.h>46#endif4748#if CONFIG_HAL_BOARD == HAL_BOARD_SITL49extern const HAL_SITL &hal;50#else51extern const AP_HAL::HAL &hal;52#endif5354extern AP_Periph_FW periph;5556#ifndef HAL_PERIPH_LOOP_DELAY_US57// delay between can loop updates. This needs to be longer on F458#if defined(STM32H7)59#define HAL_PERIPH_LOOP_DELAY_US 6460#else61#define HAL_PERIPH_LOOP_DELAY_US 102462#endif63#endif6465// timeout all frames at 1s66#define CAN_FRAME_TIMEOUT 1000000ULL6768#define DEBUG_PKTS 06970#if HAL_PERIPH_CAN_MIRROR71#ifndef HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE72#define HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE 6473#endif74#endif //HAL_PERIPH_CAN_MIRROR7576#ifndef HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF77// When enabled, can_printf() strings longer than the droneCAN max text length (90 chars)78// are split into multiple packets instead of truncating the string. This is79// especially helpful with HAL_GCS_ENABLED where libraries use the mavlink80// send_text() method where we support strings up to 256 chars by splitting them81// up into multiple 50 char mavlink packets.82#define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF (BOARD_FLASH_SIZE >= 1024)83#endif8485static struct instance_t {86uint8_t index;8788#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS89AP_HAL::CANIface* iface;90#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL91HALSITL::CANIface* iface;92#endif9394#if HAL_PERIPH_CAN_MIRROR95#if HAL_NUM_CAN_IFACES < 296#error "Can't use HAL_PERIPH_CAN_MIRROR if there are not at least 2 HAL_NUM_CAN_IFACES"97#endif98ObjectBuffer<AP_HAL::CANFrame> *mirror_queue;99uint8_t mirror_fail_count;100#endif // HAL_PERIPH_CAN_MIRROR101} instances[HAL_NUM_CAN_IFACES];102103104#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) && (HAL_NUM_CAN_IFACES >= 2)105static ioline_t can_term_lines[] = {106HAL_GPIO_PIN_TERMCAN1107108#if HAL_NUM_CAN_IFACES > 2109#ifdef HAL_GPIO_PIN_TERMCAN2110,HAL_GPIO_PIN_TERMCAN2111#else112#error "Only one Can Terminator defined with over two CAN Ifaces"113#endif114#endif115116#if HAL_NUM_CAN_IFACES > 2117#ifdef HAL_GPIO_PIN_TERMCAN3118,HAL_GPIO_PIN_TERMCAN3119#else120#error "Only two Can Terminator defined with three CAN Ifaces"121#endif122#endif123124};125#endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1)126127uint8_t user_set_node_id = HAL_CAN_DEFAULT_NODE_ID;128129#ifndef AP_PERIPH_PROBE_CONTINUOUS130#define AP_PERIPH_PROBE_CONTINUOUS 0131#endif132133#ifndef AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz134#define AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz 1135#endif136137#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS138ChibiOS::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];139#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL140HALSITL::CANIface* AP_Periph_FW::can_iface_periph[HAL_NUM_CAN_IFACES];141#endif142143#if AP_CAN_SLCAN_ENABLED144SLCAN::CANIface AP_Periph_FW::slcan_interface;145#endif146147#ifdef EXT_FLASH_SIZE_MB148static_assert(EXT_FLASH_SIZE_MB == 0, "DroneCAN bootloader cannot support external flash");149#endif150151/*152* Node status variables153*/154static uavcan_protocol_NodeStatus node_status;155#if HAL_ENABLE_SENDING_STATS156static dronecan_protocol_Stats protocol_stats;157#endif158/**159* Returns a pseudo random integer in a given range160*/161static uint16_t get_random_range(uint16_t range)162{163return get_random16() % range;164}165166167/*168get cpu unique ID169*/170static void readUniqueID(uint8_t* out_uid)171{172uint8_t len = sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data);173memset(out_uid, 0, len);174hal.util->get_system_id_unformatted(out_uid, len);175}176177178/*179handle a GET_NODE_INFO request180*/181void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance,182CanardRxTransfer* transfer)183{184uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE];185uavcan_protocol_GetNodeInfoResponse pkt {};186187node_status.uptime_sec = AP_HAL::millis() / 1000U;188189pkt.status = node_status;190pkt.software_version.major = AP::fwversion().major;191pkt.software_version.minor = AP::fwversion().minor;192pkt.software_version.optional_field_flags = UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_VCS_COMMIT | UAVCAN_PROTOCOL_SOFTWAREVERSION_OPTIONAL_FIELD_FLAG_IMAGE_CRC;193pkt.software_version.vcs_commit = app_descriptor.git_hash;194uint32_t *crc = (uint32_t *)&pkt.software_version.image_crc;195crc[0] = app_descriptor.image_crc1;196crc[1] = app_descriptor.image_crc2;197198readUniqueID(pkt.hardware_version.unique_id);199200// use hw major/minor for APJ_BOARD_ID so we know what fw is201// compatible with this hardware202pkt.hardware_version.major = APJ_BOARD_ID >> 8;203pkt.hardware_version.minor = APJ_BOARD_ID & 0xFF;204205if (g.serial_number > 0) {206hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s(%u)", CAN_APP_NODE_NAME, (unsigned)g.serial_number);207} else {208hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);209}210pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));211212uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !canfdout());213214canard_respond(canard_instance,215transfer,216UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE,217UAVCAN_PROTOCOL_GETNODEINFO_ID,218&buffer[0],219total_size);220}221222// compatability code added Mar 2024 for 4.6:223#ifndef AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED224#define AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED 1225#endif226227/*228handle parameter GetSet request229*/230void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer)231{232// param fetch all can take a long time, so pat watchdog233stm32_watchdog_pat();234235uavcan_protocol_param_GetSetRequest req;236if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) {237return;238}239240uavcan_protocol_param_GetSetResponse pkt {};241242AP_Param *vp;243enum ap_var_type ptype;244245if (req.name.len != 0 && req.name.len > AP_MAX_NAME_SIZE) {246vp = nullptr;247} else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) {248memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len);249#if AP_PERIPH_GPS_TYPE_COMPATABILITY_ENABLED250// cope with older versions of ArduPilot attempting to251// auto-configure AP_Periph using "GPS_TYPE" by252// auto-converting to "GPS1_TYPE":253if (strncmp((char*)req.name.data, "GPS_TYPE", req.name.len) == 0) {254vp = AP_Param::find("GPS1_TYPE", &ptype);255} else {256vp = AP_Param::find((char *)pkt.name.data, &ptype);257}258#else259vp = AP_Param::find((char *)pkt.name.data, &ptype);260#endif261} else {262AP_Param::ParamToken token {};263vp = AP_Param::find_by_index(req.index, &ptype, &token);264if (vp != nullptr) {265vp->copy_name_token(token, (char *)pkt.name.data, AP_MAX_NAME_SIZE+1, true);266}267}268if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) {269// param set270switch (ptype) {271case AP_PARAM_INT8:272if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {273return;274}275((AP_Int8 *)vp)->set_and_save_ifchanged(req.value.integer_value);276break;277case AP_PARAM_INT16:278if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {279return;280}281((AP_Int16 *)vp)->set_and_save_ifchanged(req.value.integer_value);282break;283case AP_PARAM_INT32:284if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {285return;286}287((AP_Int32 *)vp)->set_and_save_ifchanged(req.value.integer_value);288break;289case AP_PARAM_FLOAT:290if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) {291return;292}293((AP_Float *)vp)->set_and_save_ifchanged(req.value.real_value);294break;295default:296return;297}298}299if (vp != nullptr) {300switch (ptype) {301case AP_PARAM_INT8:302pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;303pkt.value.integer_value = ((AP_Int8 *)vp)->get();304break;305case AP_PARAM_INT16:306pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;307pkt.value.integer_value = ((AP_Int16 *)vp)->get();308break;309case AP_PARAM_INT32:310pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;311pkt.value.integer_value = ((AP_Int32 *)vp)->get();312break;313case AP_PARAM_FLOAT:314pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;315pkt.value.real_value = ((AP_Float *)vp)->get();316break;317default:318return;319}320pkt.name.len = strnlen((char *)pkt.name.data, sizeof(pkt.name.data));321}322323uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE];324uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout());325326canard_respond(canard_instance,327transfer,328UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE,329UAVCAN_PROTOCOL_PARAM_GETSET_ID,330&buffer[0],331total_size);332}333334/*335handle parameter executeopcode request336*/337void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer)338{339uavcan_protocol_param_ExecuteOpcodeRequest req;340if (uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &req)) {341return;342}343if (req.opcode == UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_ERASE) {344StorageManager::erase();345AP_Param::erase_all();346AP_Param::load_all();347AP_Param::setup_sketch_defaults();348#ifdef HAL_PERIPH_ENABLE_GPS349AP_Param::setup_object_defaults(&gps, gps.var_info);350#endif351#ifdef HAL_PERIPH_ENABLE_BATTERY352AP_Param::setup_object_defaults(&battery, battery_lib.var_info);353#endif354#ifdef HAL_PERIPH_ENABLE_MAG355AP_Param::setup_object_defaults(&compass, compass.var_info);356#endif357#ifdef HAL_PERIPH_ENABLE_BARO358AP_Param::setup_object_defaults(&baro, baro.var_info);359#endif360#ifdef HAL_PERIPH_ENABLE_AIRSPEED361AP_Param::setup_object_defaults(&airspeed, airspeed.var_info);362#endif363#ifdef HAL_PERIPH_ENABLE_RANGEFINDER364AP_Param::setup_object_defaults(&rangefinder, rangefinder.var_info);365#endif366}367368uavcan_protocol_param_ExecuteOpcodeResponse pkt {};369370pkt.ok = true;371372uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE];373uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout());374375canard_respond(canard_instance,376transfer,377UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE,378UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID,379&buffer[0],380total_size);381}382383void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer)384{385#if HAL_RAM_RESERVE_START >= 256386// setup information on firmware request at start of ram387auto *comms = (struct app_bootloader_comms *)HAL_RAM0_START;388if (comms->magic != APP_BOOTLOADER_COMMS_MAGIC) {389memset(comms, 0, sizeof(*comms));390}391comms->magic = APP_BOOTLOADER_COMMS_MAGIC;392393uavcan_protocol_file_BeginFirmwareUpdateRequest req;394if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &req)) {395return;396}397398comms->server_node_id = req.source_node_id;399if (comms->server_node_id == 0) {400comms->server_node_id = transfer->source_node_id;401}402memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len);403comms->my_node_id = canardGetLocalNodeID(canard_instance);404405uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE];406uavcan_protocol_file_BeginFirmwareUpdateResponse reply {};407reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK;408409uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !canfdout());410canard_respond(canard_instance,411transfer,412UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE,413UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID,414&buffer[0],415total_size);416uint8_t count = 50;417while (count--) {418processTx();419hal.scheduler->delay(1);420}421#endif422423// instant reboot, with backup register used to give bootloader424// the node_id425prepare_reboot();426#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS427set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(canard_instance)));428NVIC_SystemReset();429#endif430}431432void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer)433{434// Rule C - updating the randomized time interval435dronecan.send_next_node_id_allocation_request_at_ms =436AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +437get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);438439if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID)440{441printf("Allocation request from another allocatee\n");442dronecan.node_id_allocation_unique_id_offset = 0;443return;444}445446// Copying the unique ID from the message447uavcan_protocol_dynamic_node_id_Allocation msg;448449if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) {450// failed decode451return;452}453454// Obtaining the local unique ID455uint8_t my_unique_id[sizeof(msg.unique_id.data)];456readUniqueID(my_unique_id);457458// Matching the received UID against the local one459if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) {460printf("Mismatching allocation response\n");461dronecan.node_id_allocation_unique_id_offset = 0;462return; // No match, return463}464465if (msg.unique_id.len < sizeof(msg.unique_id.data)) {466// The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout.467dronecan.node_id_allocation_unique_id_offset = msg.unique_id.len;468dronecan.send_next_node_id_allocation_request_at_ms -= UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS;469470printf("Matching allocation response: %d\n", msg.unique_id.len);471} else if (msg.node_id != CANARD_BROADCAST_NODE_ID) { // new ID valid? (if not we will time out and start over)472// Allocation complete - copying the allocated node ID from the message473canardSetLocalNodeID(canard_instance, msg.node_id);474printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id);475476#if defined(HAL_PERIPH_ENABLE_GPS) && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE477if (g.gps_mb_only_can_port) {478// we need to assign the unallocated port to be used for Moving Baseline only479gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES;480if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {481// copy node id from the primary iface482canardSetLocalNodeID(&dronecan.canard, msg.node_id);483#ifdef HAL_GPIO_PIN_TERMCAN1484// also terminate the line as we don't have any other device on this port485palWriteLine(can_term_lines[gps_mb_can_port], 1);486#endif487}488}489#endif490}491}492493494#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)495static uint8_t safety_state;496497/*498handle SafetyState499*/500void AP_Periph_FW::handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)501{502ardupilot_indication_SafetyState req;503if (ardupilot_indication_SafetyState_decode(transfer, &req)) {504return;505}506safety_state = req.status;507#if AP_PERIPH_SAFETY_SWITCH_ENABLED508rcout_handle_safety_state(safety_state);509#endif510}511#endif // HAL_GPIO_PIN_SAFE_LED512513/*514handle ArmingStatus515*/516void AP_Periph_FW::handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer)517{518uavcan_equipment_safety_ArmingStatus req;519if (uavcan_equipment_safety_ArmingStatus_decode(transfer, &req)) {520return;521}522hal.util->set_soft_armed(req.status == UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED);523}524525526527#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)528void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue)529{530#ifdef HAL_PERIPH_ENABLE_NOTIFY531notify.handle_rgb(red, green, blue);532#ifdef HAL_PERIPH_ENABLE_RC_OUT533rcout_has_new_data_to_update = true;534#endif // HAL_PERIPH_ENABLE_RC_OUT535#endif // HAL_PERIPH_ENABLE_NOTIFY536537#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY538hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, red, green, blue);539hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);540#endif // HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY541542#ifdef HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY543{544const uint8_t i2c_address = 0x38;545static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;546if (!dev) {547dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));548}549WITH_SEMAPHORE(dev->get_semaphore());550dev->set_retries(0);551uint8_t v = 0x3f; // enable LED552dev->transfer(&v, 1, nullptr, 0);553v = 0x40 | red >> 3; // red554dev->transfer(&v, 1, nullptr, 0);555v = 0x60 | green >> 3; // green556dev->transfer(&v, 1, nullptr, 0);557v = 0x80 | blue >> 3; // blue558dev->transfer(&v, 1, nullptr, 0);559}560#endif // HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY561562#ifdef HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY563{564const uint8_t i2c_address = 0x38;565static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;566if (!dev) {567dev = std::move(hal.i2c_mgr->get_device(0, i2c_address));568}569WITH_SEMAPHORE(dev->get_semaphore());570dev->set_retries(0);571uint8_t v = 0x3f; // enable LED572dev->transfer(&v, 1, nullptr, 0);573v = 0x40 | blue >> 3; // blue574dev->transfer(&v, 1, nullptr, 0);575v = 0x60 | green >> 3; // green576dev->transfer(&v, 1, nullptr, 0);577v = 0x80 | red >> 3; // red578dev->transfer(&v, 1, nullptr, 0);579}580#endif // HAL_PERIPH_ENABLE_NCP5623_BGR_LED_WITHOUT_NOTIFY581#ifdef HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY582{583#define TOSHIBA_LED_PWM0 0x01 // pwm0 register584#define TOSHIBA_LED_ENABLE 0x04 // enable register585#define TOSHIBA_LED_I2C_ADDR 0x55 // default I2C bus address586587static AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev_toshiba;588if (!dev_toshiba) {589dev_toshiba = std::move(hal.i2c_mgr->get_device(0, TOSHIBA_LED_I2C_ADDR));590}591WITH_SEMAPHORE(dev_toshiba->get_semaphore());592dev_toshiba->set_retries(0); // use 0 because this is running on main thread.593594// enable the led595dev_toshiba->write_register(TOSHIBA_LED_ENABLE, 0x03);596597/* 4-bit for each color */598uint8_t val[4] = {599TOSHIBA_LED_PWM0,600(uint8_t)(blue >> 4),601(uint8_t)(green / 16),602(uint8_t)(red / 16)603};604dev_toshiba->transfer(val, sizeof(val), nullptr, 0);605}606#endif // HAL_PERIPH_ENABLE_TOSHIBA_LED_WITHOUT_NOTIFY607}608609/*610handle lightscommand611*/612void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)613{614uavcan_equipment_indication_LightsCommand req;615if (uavcan_equipment_indication_LightsCommand_decode(transfer, &req)) {616return;617}618for (uint8_t i=0; i<req.commands.len; i++) {619uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];620// to get the right color proportions we scale the green so that is uses the621// same number of bits as red and blue622uint8_t red = cmd.color.red<<3U;623uint8_t green = (cmd.color.green>>1U)<<3U;624uint8_t blue = cmd.color.blue<<3U;625#ifdef HAL_PERIPH_ENABLE_NOTIFY626const int8_t brightness = notify.get_rgb_led_brightness_percent();627#elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY)628const int8_t brightness = g.led_brightness;629#endif630if (brightness != 100 && brightness >= 0) {631const float scale = brightness * 0.01;632red = constrain_int16(red * scale, 0, 255);633green = constrain_int16(green * scale, 0, 255);634blue = constrain_int16(blue * scale, 0, 255);635}636set_rgb_led(red, green, blue);637}638}639#endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY640641#ifdef HAL_PERIPH_ENABLE_RC_OUT642void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer)643{644uavcan_equipment_esc_RawCommand cmd;645if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) {646return;647}648rcout_esc(cmd.cmd.data, cmd.cmd.len);649650// Update internal copy for disabling output to ESC when CAN packets are lost651last_esc_num_channels = cmd.cmd.len;652last_esc_raw_command_ms = AP_HAL::millis();653}654655void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer)656{657uavcan_equipment_actuator_ArrayCommand cmd;658if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) {659return;660}661662for (uint8_t i=0; i < cmd.commands.len; i++) {663const auto &c = cmd.commands.data[i];664switch (c.command_type) {665case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS:666rcout_srv_unitless(c.actuator_id, c.command_value);667break;668case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM:669rcout_srv_PWM(c.actuator_id, c.command_value);670break;671}672}673}674#endif // HAL_PERIPH_ENABLE_RC_OUT675676#if defined(HAL_PERIPH_ENABLE_NOTIFY)677void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer)678{679ardupilot_indication_NotifyState msg;680if (ardupilot_indication_NotifyState_decode(transfer, &msg)) {681return;682}683if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) {684uint16_t tmp = 0;685memcpy(&tmp, msg.aux_data.data, sizeof(tmp));686yaw_earth = radians((float)tmp * 0.01f);687}688vehicle_state = msg.vehicle_state;689last_vehicle_state = AP_HAL::millis();690}691#endif // HAL_PERIPH_ENABLE_NOTIFY692693#ifdef HAL_GPIO_PIN_SAFE_LED694/*695update safety LED696*/697void AP_Periph_FW::can_safety_LED_update(void)698{699static uint32_t last_update_ms;700switch (safety_state) {701case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF:702palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON);703break;704case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: {705uint32_t now = AP_HAL::millis();706if (now - last_update_ms > 100) {707last_update_ms = now;708static uint8_t led_counter;709const uint16_t led_pattern = 0x5500;710led_counter = (led_counter+1) % 16;711palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U << led_counter))?!SAFE_LED_ON:SAFE_LED_ON);712}713break;714}715default:716palWriteLine(HAL_GPIO_PIN_SAFE_LED, !SAFE_LED_ON);717break;718}719}720#endif // HAL_GPIO_PIN_SAFE_LED721722723#ifdef HAL_GPIO_PIN_SAFE_BUTTON724#ifndef HAL_SAFE_BUTTON_ON725#define HAL_SAFE_BUTTON_ON 1726#endif727/*728update safety button729*/730void AP_Periph_FW::can_safety_button_update(void)731{732static uint32_t last_update_ms;733static uint8_t counter;734uint32_t now = AP_HAL::millis();735// send at 10Hz when pressed736if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) {737counter = 0;738return;739}740if (now - last_update_ms < 100) {741return;742}743if (counter < 255) {744counter++;745}746747last_update_ms = now;748ardupilot_indication_Button pkt {};749pkt.button = ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY;750pkt.press_time = counter;751752uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE];753uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout());754755canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE,756ARDUPILOT_INDICATION_BUTTON_ID,757CANARD_TRANSFER_PRIORITY_LOW,758&buffer[0],759total_size);760}761#endif // HAL_GPIO_PIN_SAFE_BUTTON762763/**764* This callback is invoked by the library when a new message or request or response is received.765*/766void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance,767CanardRxTransfer* transfer)768{769#ifdef HAL_GPIO_PIN_LED_CAN1770palToggleLine(HAL_GPIO_PIN_LED_CAN1);771#endif772773#if HAL_CANFD_SUPPORTED774// enable tao for decoding when not on CANFD775transfer->tao = !transfer->canfd;776#endif777778/*779* Dynamic node ID allocation protocol.780* Taking this branch only if we don't have a node ID, ignoring otherwise.781*/782if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) {783if (transfer->transfer_type == CanardTransferTypeBroadcast &&784transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) {785handle_allocation_response(canard_instance, transfer);786}787return;788}789790switch (transfer->data_type_id) {791case UAVCAN_PROTOCOL_GETNODEINFO_ID:792handle_get_node_info(canard_instance, transfer);793break;794795case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:796handle_begin_firmware_update(canard_instance, transfer);797break;798799case UAVCAN_PROTOCOL_RESTARTNODE_ID: {800printf("RestartNode\n");801uavcan_protocol_RestartNodeResponse pkt {802ok: true,803};804uint8_t buffer[UAVCAN_PROTOCOL_RESTARTNODE_RESPONSE_MAX_SIZE];805uint16_t total_size = uavcan_protocol_RestartNodeResponse_encode(&pkt, buffer, !canfdout());806canard_respond(canard_instance,807transfer,808UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE,809UAVCAN_PROTOCOL_RESTARTNODE_ID,810&buffer[0],811total_size);812813// schedule a reboot to occur814reboot_request_ms = AP_HAL::millis();815}816break;817818case UAVCAN_PROTOCOL_PARAM_GETSET_ID:819handle_param_getset(canard_instance, transfer);820break;821822case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:823handle_param_executeopcode(canard_instance, transfer);824break;825826#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)827case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:828handle_beep_command(canard_instance, transfer);829break;830#endif831832#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)833case ARDUPILOT_INDICATION_SAFETYSTATE_ID:834handle_safety_state(canard_instance, transfer);835break;836#endif837838case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:839handle_arming_status(canard_instance, transfer);840break;841842#ifdef HAL_PERIPH_ENABLE_GPS843case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:844handle_RTCMStream(canard_instance, transfer);845break;846847#if GPS_MOVING_BASELINE848case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:849handle_MovingBaselineData(canard_instance, transfer);850break;851#endif852#endif // HAL_PERIPH_ENABLE_GPS853854#if AP_UART_MONITOR_ENABLED855case UAVCAN_TUNNEL_TARGETTED_ID:856handle_tunnel_Targetted(canard_instance, transfer);857break;858#endif859860#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)861case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:862handle_lightscommand(canard_instance, transfer);863break;864#endif865866#ifdef HAL_PERIPH_ENABLE_RC_OUT867case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:868handle_esc_rawcommand(canard_instance, transfer);869break;870871case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:872handle_act_command(canard_instance, transfer);873break;874#endif875876#ifdef HAL_PERIPH_ENABLE_NOTIFY877case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:878handle_notify_state(canard_instance, transfer);879break;880#endif881882#ifdef HAL_PERIPH_ENABLE_RELAY883case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:884handle_hardpoint_command(canard_instance, transfer);885break;886#endif887888}889}890891/**892* This callback is invoked by the library when a new message or request or response is received.893*/894static void onTransferReceived_trampoline(CanardInstance* canard_instance,895CanardRxTransfer* transfer)896{897AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;898fw->onTransferReceived(canard_instance, transfer);899}900901902/**903* This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received904* by the local node.905* If the callback returns true, the library will receive the transfer.906* If the callback returns false, the library will ignore the transfer.907* All transfers that are addressed to other nodes are always ignored.908*/909bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance,910uint64_t* out_data_type_signature,911uint16_t data_type_id,912CanardTransferType transfer_type,913uint8_t source_node_id)914{915(void)source_node_id;916917if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID)918{919/*920* If we're in the process of allocation of dynamic node ID, accept only relevant transfers.921*/922if ((transfer_type == CanardTransferTypeBroadcast) &&923(data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID))924{925*out_data_type_signature = UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE;926return true;927}928return false;929}930931switch (data_type_id) {932case UAVCAN_PROTOCOL_GETNODEINFO_ID:933*out_data_type_signature = UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE;934return true;935case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID:936*out_data_type_signature = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE;937return true;938case UAVCAN_PROTOCOL_RESTARTNODE_ID:939*out_data_type_signature = UAVCAN_PROTOCOL_RESTARTNODE_SIGNATURE;940return true;941case UAVCAN_PROTOCOL_PARAM_GETSET_ID:942*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE;943return true;944case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID:945*out_data_type_signature = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE;946return true;947#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)948case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID:949*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_SIGNATURE;950return true;951#endif952#if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT)953case ARDUPILOT_INDICATION_SAFETYSTATE_ID:954*out_data_type_signature = ARDUPILOT_INDICATION_SAFETYSTATE_SIGNATURE;955return true;956#endif957case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID:958*out_data_type_signature = UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_SIGNATURE;959return true;960#if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY)961case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID:962*out_data_type_signature = UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_SIGNATURE;963return true;964#endif965#ifdef HAL_PERIPH_ENABLE_GPS966case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID:967*out_data_type_signature = UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_SIGNATURE;968return true;969970#if GPS_MOVING_BASELINE971case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID:972*out_data_type_signature = ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE;973return true;974#endif975#endif // HAL_PERIPH_ENABLE_GPS976977#if AP_UART_MONITOR_ENABLED978case UAVCAN_TUNNEL_TARGETTED_ID:979*out_data_type_signature = UAVCAN_TUNNEL_TARGETTED_SIGNATURE;980return true;981#endif982983#ifdef HAL_PERIPH_ENABLE_RC_OUT984case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID:985*out_data_type_signature = UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_SIGNATURE;986return true;987988case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID:989*out_data_type_signature = UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_SIGNATURE;990return true;991#endif992#if defined(HAL_PERIPH_ENABLE_NOTIFY)993case ARDUPILOT_INDICATION_NOTIFYSTATE_ID:994*out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE;995return true;996#endif997#ifdef HAL_PERIPH_ENABLE_RELAY998case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID:999*out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE;1000return true;1001#endif1002default:1003break;1004}10051006return false;1007}10081009static bool shouldAcceptTransfer_trampoline(const CanardInstance* canard_instance,1010uint64_t* out_data_type_signature,1011uint16_t data_type_id,1012CanardTransferType transfer_type,1013uint8_t source_node_id)1014{1015AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference;1016return fw->shouldAcceptTransfer(canard_instance, out_data_type_signature, data_type_id, transfer_type, source_node_id);1017}10181019void AP_Periph_FW::cleanup_stale_transactions(uint64_t timestamp_usec)1020{1021canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec);1022}10231024uint8_t *AP_Periph_FW::get_tid_ptr(uint32_t transfer_desc)1025{1026// check head1027if (!dronecan.tid_map_head) {1028dronecan.tid_map_head = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));1029if (dronecan.tid_map_head == nullptr) {1030return nullptr;1031}1032dronecan.tid_map_head->transfer_desc = transfer_desc;1033dronecan.tid_map_head->next = nullptr;1034return &dronecan.tid_map_head->tid;1035} else if (dronecan.tid_map_head->transfer_desc == transfer_desc) {1036return &dronecan.tid_map_head->tid;1037}10381039// search through the list for an existing entry1040dronecan_protocol_t::tid_map *tid_map_ptr = dronecan.tid_map_head;1041while(tid_map_ptr->next) {1042tid_map_ptr = tid_map_ptr->next;1043if (tid_map_ptr->transfer_desc == transfer_desc) {1044return &tid_map_ptr->tid;1045}1046}10471048// create a new entry, if not found1049tid_map_ptr->next = (dronecan_protocol_t::tid_map*)calloc(1, sizeof(dronecan_protocol_t::tid_map));1050if (tid_map_ptr->next == nullptr) {1051return nullptr;1052}1053tid_map_ptr->next->transfer_desc = transfer_desc;1054tid_map_ptr->next->next = nullptr;1055return &tid_map_ptr->next->tid;1056}10571058bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature,1059uint16_t data_type_id,1060uint8_t priority,1061const void* payload,1062uint16_t payload_len,1063uint8_t iface_mask)1064{1065WITH_SEMAPHORE(canard_broadcast_semaphore);1066const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID;1067if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) {1068return false;1069}10701071uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(data_type_signature, data_type_id, 0, CANARD_BROADCAST_NODE_ID));1072if (tid_ptr == nullptr) {1073return false;1074}10751076// create transfer object1077CanardTxTransfer transfer_object = {1078.transfer_type = CanardTransferTypeBroadcast,1079.data_type_signature = data_type_signature,1080.data_type_id = data_type_id,1081.inout_transfer_id = tid_ptr,1082.priority = priority,1083.payload = (uint8_t*)payload,1084.payload_len = payload_len,1085#if CANARD_ENABLE_CANFD1086.canfd = is_dna? false : canfdout(),1087#endif1088.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,1089#if CANARD_MULTI_IFACE1090.iface_mask = iface_mask==0 ? uint8_t(IFACE_ALL) : iface_mask,1091#endif1092};1093const int16_t res = canardBroadcastObj(&dronecan.canard, &transfer_object);10941095#if DEBUG_PKTS1096if (res < 0) {1097can_printf("Tx error %d\n", res);1098}1099#endif1100#if HAL_ENABLE_SENDING_STATS1101if (res <= 0) {1102protocol_stats.tx_errors++;1103} else {1104protocol_stats.tx_frames += res;1105}1106#endif1107return res > 0;1108}11091110/*1111send a response1112*/1113bool AP_Periph_FW::canard_respond(CanardInstance* canard_instance,1114CanardRxTransfer *transfer,1115uint64_t data_type_signature,1116uint16_t data_type_id,1117const uint8_t *payload,1118uint16_t payload_len)1119{1120CanardTxTransfer transfer_object = {1121.transfer_type = CanardTransferTypeResponse,1122.data_type_signature = data_type_signature,1123.data_type_id = data_type_id,1124.inout_transfer_id = &transfer->transfer_id,1125.priority = transfer->priority,1126.payload = payload,1127.payload_len = payload_len,1128#if CANARD_ENABLE_CANFD1129.canfd = canfdout(),1130#endif1131.deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT,1132#if CANARD_MULTI_IFACE1133.iface_mask = IFACE_ALL,1134#endif1135};1136const auto res = canardRequestOrRespondObj(canard_instance,1137transfer->source_node_id,1138&transfer_object);1139#if DEBUG_PKTS1140if (res < 0) {1141can_printf("Tx error %d\n", res);1142}1143#endif1144#if HAL_ENABLE_SENDING_STATS1145if (res <= 0) {1146protocol_stats.tx_errors++;1147} else {1148protocol_stats.tx_frames += res;1149}1150#endif1151return res > 0;1152}11531154void AP_Periph_FW::processTx(void)1155{1156for (CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) {1157AP_HAL::CANFrame txmsg {};1158txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len);1159memcpy(txmsg.data, txf->data, txf->data_len);1160txmsg.id = (txf->id | AP_HAL::CANFrame::FlagEFF);1161#if HAL_CANFD_SUPPORTED1162txmsg.canfd = txf->canfd;1163#endif1164// push message with 1s timeout1165bool sent = true;1166const uint64_t now_us = AP_HAL::micros64();1167const uint64_t deadline = now_us + 1000000U;1168// try sending to all interfaces1169for (auto &_ins : instances) {1170if (_ins.iface == NULL) {1171continue;1172}1173#if CANARD_MULTI_IFACE1174if (!(txf->iface_mask & (1U<<_ins.index))) {1175continue;1176}1177#endif1178#if HAL_NUM_CAN_IFACES >= 21179if (can_protocol_cached[_ins.index] != AP_CAN::Protocol::DroneCAN) {1180continue;1181}1182#endif1183if (_ins.iface->send(txmsg, deadline, 0) <= 0) {1184/*1185We were not able to queue the frame for1186sending. Only mark the send as failing if the1187interface is active. We consider an interface as1188active if it has had a successful transmit in the1189last 2 seconds1190*/1191volatile const auto *stats = _ins.iface->get_statistics();1192uint64_t last_transmit_us = stats->last_transmit_us;1193if (stats == nullptr || AP_HAL::micros64() - last_transmit_us < 2000000UL) {1194sent = false;1195}1196} else {1197#if CANARD_MULTI_IFACE1198txf->iface_mask &= ~(1U<<_ins.index);1199#endif1200}1201}1202if (sent) {1203canardPopTxQueue(&dronecan.canard);1204dronecan.tx_fail_count = 0;1205} else {1206// exit and try again later. If we fail 8 times in a row1207// then cleanup any stale transfers to keep the queue from1208// filling1209if (dronecan.tx_fail_count < 8) {1210dronecan.tx_fail_count++;1211} else {1212#if HAL_ENABLE_SENDING_STATS1213protocol_stats.tx_errors++;1214#endif1215dronecan.tx_fail_count = 0;1216cleanup_stale_transactions(now_us);1217}1218break;1219}1220}1221}12221223#if HAL_ENABLE_SENDING_STATS1224void AP_Periph_FW::update_rx_protocol_stats(int16_t res)1225{1226switch (res) {1227case CANARD_OK:1228protocol_stats.rx_frames++;1229break;1230case -CANARD_ERROR_OUT_OF_MEMORY:1231protocol_stats.rx_error_oom++;1232break;1233case -CANARD_ERROR_INTERNAL:1234protocol_stats.rx_error_internal++;1235break;1236case -CANARD_ERROR_RX_INCOMPATIBLE_PACKET:1237protocol_stats.rx_ignored_not_wanted++;1238break;1239case -CANARD_ERROR_RX_WRONG_ADDRESS:1240protocol_stats.rx_ignored_wrong_address++;1241break;1242case -CANARD_ERROR_RX_NOT_WANTED:1243protocol_stats.rx_ignored_not_wanted++;1244break;1245case -CANARD_ERROR_RX_MISSED_START:1246protocol_stats.rx_error_missed_start++;1247break;1248case -CANARD_ERROR_RX_WRONG_TOGGLE:1249protocol_stats.rx_error_wrong_toggle++;1250break;1251case -CANARD_ERROR_RX_UNEXPECTED_TID:1252protocol_stats.rx_ignored_unexpected_tid++;1253break;1254case -CANARD_ERROR_RX_SHORT_FRAME:1255protocol_stats.rx_error_short_frame++;1256break;1257case -CANARD_ERROR_RX_BAD_CRC:1258protocol_stats.rx_error_bad_crc++;1259break;1260default:1261// mark all other errors as internal1262protocol_stats.rx_error_internal++;1263break;1264}1265}1266#endif12671268void AP_Periph_FW::processRx(void)1269{1270AP_HAL::CANFrame rxmsg;1271for (auto &instance : instances) {1272if (instance.iface == NULL) {1273continue;1274}1275#if HAL_NUM_CAN_IFACES >= 21276if (can_protocol_cached[instance.index] != AP_CAN::Protocol::DroneCAN) {1277continue;1278}1279#endif1280while (true) {1281bool read_select = true;1282bool write_select = false;1283instance.iface->select(read_select, write_select, nullptr, 0);1284if (!read_select) { // No data pending1285break;1286}1287CanardCANFrame rx_frame {};12881289//palToggleLine(HAL_GPIO_PIN_LED);1290uint64_t timestamp;1291AP_HAL::CANIface::CanIOFlags flags;1292if (instance.iface->receive(rxmsg, timestamp, flags) <= 0) {1293break;1294}1295#if HAL_PERIPH_CAN_MIRROR1296for (auto &other_instance : instances) {1297if (other_instance.mirror_queue == nullptr) { // we aren't mirroring here, or failed on memory1298continue;1299}1300if (other_instance.index == instance.index) { // don't self add1301continue;1302}1303other_instance.mirror_queue->push(rxmsg);1304}1305#endif // HAL_PERIPH_CAN_MIRROR1306rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc);1307memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len);1308#if HAL_CANFD_SUPPORTED1309rx_frame.canfd = rxmsg.canfd;1310#endif1311rx_frame.id = rxmsg.id;1312#if CANARD_MULTI_IFACE1313rx_frame.iface_id = instance.index;1314#endif13151316const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp);1317#if HAL_ENABLE_SENDING_STATS1318if (res == -CANARD_ERROR_RX_MISSED_START) {1319// this might remaining frames from a message that we don't accept, so check1320uint64_t dummy_signature;1321if (shouldAcceptTransfer(&dronecan.canard,1322&dummy_signature,1323extractDataType(rx_frame.id),1324extractTransferType(rx_frame.id),13251)) { // doesn't matter what we pass here1326update_rx_protocol_stats(res);1327} else {1328protocol_stats.rx_ignored_not_wanted++;1329}1330} else {1331update_rx_protocol_stats(res);1332}1333#else1334(void)res;1335#endif1336}1337}1338}13391340#if HAL_PERIPH_CAN_MIRROR1341void AP_Periph_FW::processMirror(void)1342{1343const uint64_t deadline = AP_HAL::micros64() + 1000000;13441345for (auto &ins : instances) {1346if (ins.iface == nullptr || ins.mirror_queue == nullptr) { // can't send on a null interface1347continue;1348}13491350const uint32_t pending = ins.mirror_queue->available();1351for (uint32_t i = 0; i < pending; i++) { // limit how long we can loop1352AP_HAL::CANFrame txmsg {};13531354if (!ins.mirror_queue->peek(txmsg)) {1355break;1356}13571358if (ins.iface->send(txmsg, deadline, 0) <= 0) {1359if (ins.mirror_fail_count < 8) {1360ins.mirror_fail_count++;1361} else {1362ins.mirror_queue->pop();1363}1364break;1365} else {1366ins.mirror_fail_count = 0;1367ins.mirror_queue->pop();1368}1369}1370}1371}1372#endif // HAL_PERIPH_CAN_MIRROR13731374uint16_t AP_Periph_FW::pool_peak_percent()1375{1376const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&dronecan.canard);1377const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks);1378return peak_percent;1379}13801381void AP_Periph_FW::node_status_send(void)1382{1383{1384uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE];1385node_status.uptime_sec = AP_HAL::millis() / 1000U;13861387node_status.vendor_specific_status_code = MIN(hal.util->available_memory(), unsigned(UINT16_MAX));13881389uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !canfdout());13901391canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE,1392UAVCAN_PROTOCOL_NODESTATUS_ID,1393CANARD_TRANSFER_PRIORITY_LOW,1394buffer,1395len);1396}1397#if HAL_ENABLE_SENDING_STATS1398if (debug_option_is_set(AP_Periph_FW::DebugOptions::ENABLE_STATS)) {1399{1400uint8_t buffer[DRONECAN_PROTOCOL_STATS_MAX_SIZE];1401uint32_t len = dronecan_protocol_Stats_encode(&protocol_stats, buffer, !canfdout());1402canard_broadcast(DRONECAN_PROTOCOL_STATS_SIGNATURE,1403DRONECAN_PROTOCOL_STATS_ID,1404CANARD_TRANSFER_PRIORITY_LOWEST,1405buffer,1406len);1407}1408for (auto &instance : instances) {1409uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE];1410dronecan_protocol_CanStats can_stats;1411const AP_HAL::CANIface::bus_stats_t *bus_stats = instance.iface->get_statistics();1412if (bus_stats == nullptr) {1413return;1414}1415can_stats.interface = instance.index;1416can_stats.tx_requests = bus_stats->tx_requests;1417can_stats.tx_rejected = bus_stats->tx_rejected;1418can_stats.tx_overflow = bus_stats->tx_overflow;1419can_stats.tx_success = bus_stats->tx_success;1420can_stats.tx_timedout = bus_stats->tx_timedout;1421can_stats.tx_abort = bus_stats->tx_abort;1422can_stats.rx_received = bus_stats->rx_received;1423can_stats.rx_overflow = bus_stats->rx_overflow;1424can_stats.rx_errors = bus_stats->rx_errors;1425can_stats.busoff_errors = bus_stats->num_busoff_err;1426uint32_t len = dronecan_protocol_CanStats_encode(&can_stats, buffer, !canfdout());1427canard_broadcast(DRONECAN_PROTOCOL_CANSTATS_SIGNATURE,1428DRONECAN_PROTOCOL_CANSTATS_ID,1429CANARD_TRANSFER_PRIORITY_LOWEST,1430buffer,1431len);1432}1433}1434#endif1435}143614371438/**1439* This function is called at 1 Hz rate from the main loop.1440*/1441void AP_Periph_FW::process1HzTasks(uint64_t timestamp_usec)1442{1443/*1444* Purging transfers that are no longer transmitted. This will occasionally free up some memory.1445*/1446cleanup_stale_transactions(timestamp_usec);14471448/*1449* Printing the memory usage statistics.1450*/1451{1452/*1453* The recommended way to establish the minimal size of the memory pool is to stress-test the application and1454* record the worst case memory usage.1455*/14561457if (pool_peak_percent() > 70) {1458printf("WARNING: ENLARGE MEMORY POOL\n");1459}1460}14611462/*1463* Transmitting the node status message periodically.1464*/1465node_status_send();14661467#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)1468if (g.flash_bootloader.get()) {1469const uint8_t flash_bl = g.flash_bootloader.get();1470g.flash_bootloader.set_and_save_ifchanged(0);1471if (flash_bl == 42) {1472// magic developer value to test watchdog support with main loop lockup1473while (true) {1474can_printf("entering lockup\n");1475hal.scheduler->delay(100);1476}1477}1478if (flash_bl == 43) {1479// magic developer value to test watchdog support with hard fault1480can_printf("entering fault\n");1481void *foo = (void*)0xE000ED38;1482typedef void (*fptr)();1483fptr gptr = (fptr) (void *) foo;1484gptr();1485}1486EXPECT_DELAY_MS(2000);1487hal.scheduler->delay(1000);1488AP_HAL::Util::FlashBootloader res = hal.util->flash_bootloader();1489switch (res) {1490case AP_HAL::Util::FlashBootloader::OK:1491can_printf("Flash bootloader OK\n");1492break;1493case AP_HAL::Util::FlashBootloader::NO_CHANGE:1494can_printf("Bootloader unchanged\n");1495break;1496#if AP_SIGNED_FIRMWARE1497case AP_HAL::Util::FlashBootloader::NOT_SIGNED:1498can_printf("Bootloader not signed\n");1499break;1500#endif1501default:1502can_printf("Flash bootloader FAILED\n");1503break;1504}1505}1506#endif15071508#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1509if (hal.run_in_maintenance_mode()) {1510node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_MAINTENANCE;1511} else1512#endif1513{1514node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL;1515}15161517#if 01518// test code for watchdog reset1519if (AP_HAL::millis() > 15000) {1520while (true) ;1521}1522#endif1523#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS1524if (AP_HAL::millis() > 30000) {1525// use RTC to mark that we have been running fine for1526// 30s. This is used along with watchdog resets to ensure the1527// user has a chance to load a fixed firmware1528set_fast_reboot(RTC_BOOT_FWOK);1529}1530#endif1531}15321533/*1534wait for dynamic allocation of node ID1535*/1536bool AP_Periph_FW::no_iface_finished_dna = true;15371538bool AP_Periph_FW::can_do_dna()1539{1540if (canardGetLocalNodeID(&dronecan.canard) != CANARD_BROADCAST_NODE_ID) {1541AP_Periph_FW::no_iface_finished_dna = false;1542return true;1543}15441545const uint32_t now = AP_HAL::millis();15461547if (AP_Periph_FW::no_iface_finished_dna) {1548printf("Waiting for dynamic node ID allocation %x... (pool %u)\n", IFACE_ALL, pool_peak_percent());1549}15501551dronecan.send_next_node_id_allocation_request_at_ms =1552now + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS +1553get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS);15541555// Structure of the request is documented in the DSDL definition1556// See http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation1557uint8_t allocation_request[CANARD_CAN_FRAME_MAX_DATA_LEN - 1];1558allocation_request[0] = 0; // we are only called if the user has not set an ID, so request any ID15591560if (dronecan.node_id_allocation_unique_id_offset == 0) {1561allocation_request[0] |= 1; // First part of unique ID1562// set interface to try1563dronecan.dna_interface++;1564dronecan.dna_interface %= HAL_NUM_CAN_IFACES;1565}15661567uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)];1568readUniqueID(my_unique_id);15691570static const uint8_t MaxLenOfUniqueIDInRequest = 6;1571uint8_t uid_size = (uint8_t)(sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data) - dronecan.node_id_allocation_unique_id_offset);15721573if (uid_size > MaxLenOfUniqueIDInRequest) {1574uid_size = MaxLenOfUniqueIDInRequest;1575}15761577memmove(&allocation_request[1], &my_unique_id[dronecan.node_id_allocation_unique_id_offset], uid_size);15781579// Broadcasting the request1580canard_broadcast(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE,1581UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID,1582CANARD_TRANSFER_PRIORITY_LOW,1583&allocation_request[0],1584(uint16_t) (uid_size + 1));15851586// Preparing for timeout; if response is received, this value will be updated from the callback.1587dronecan.node_id_allocation_unique_id_offset = 0;1588return false;1589}15901591void AP_Periph_FW::can_start()1592{1593node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;1594node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION;1595node_status.uptime_sec = AP_HAL::millis() / 1000U;15961597if (g.can_node >= 0 && g.can_node < 128) {1598user_set_node_id = g.can_node;1599}16001601#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)1602g.flash_bootloader.set_and_save_ifchanged(0);1603#endif16041605#if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 21606bool has_uavcan_at_1MHz = false;1607for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {1608if (g.can_protocol[i] == AP_CAN::Protocol::DroneCAN && g.can_baudrate[i] == 1000000) {1609has_uavcan_at_1MHz = true;1610}1611}1612if (!has_uavcan_at_1MHz) {1613g.can_protocol[0].set_and_save(uint8_t(AP_CAN::Protocol::DroneCAN));1614g.can_baudrate[0].set_and_save(1000000);1615}1616#endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz16171618#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM1619palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, g.can_terminate[0]);1620#endif1621#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM1622palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, g.can_terminate[1]);1623#endif1624#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM1625palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, g.can_terminate[2]);1626#endif16271628for (uint8_t i=0; i<HAL_NUM_CAN_IFACES; i++) {1629#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS1630can_iface_periph[i] = NEW_NOTHROW ChibiOS::CANIface();1631#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL1632can_iface_periph[i] = NEW_NOTHROW HALSITL::CANIface();1633#endif1634instances[i].iface = can_iface_periph[i];1635instances[i].index = i;1636#if HAL_PERIPH_CAN_MIRROR1637if ((g.can_mirror_ports & (1U << i)) != 0) {1638instances[i].mirror_queue = NEW_NOTHROW ObjectBuffer<AP_HAL::CANFrame> (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE);1639}1640#endif //HAL_PERIPH_CAN_MIRROR1641#if HAL_NUM_CAN_IFACES >= 21642can_protocol_cached[i] = g.can_protocol[i];1643CANSensor::set_periph(i, can_protocol_cached[i], can_iface_periph[i]);1644#endif1645if (can_iface_periph[i] != nullptr) {1646#if HAL_CANFD_SUPPORTED1647can_iface_periph[i]->init(g.can_baudrate[i], g.can_fdbaudrate[i]*1000000U, AP_HAL::CANIface::NormalMode);1648#else1649can_iface_periph[i]->init(g.can_baudrate[i], AP_HAL::CANIface::NormalMode);1650#endif1651}1652}16531654#if AP_CAN_SLCAN_ENABLED1655const uint8_t slcan_selected_index = g.can_slcan_cport - 1;1656if (slcan_selected_index < HAL_NUM_CAN_IFACES) {1657slcan_interface.set_can_iface(can_iface_periph[slcan_selected_index]);1658instances[slcan_selected_index].iface = (AP_HAL::CANIface*)&slcan_interface;16591660// ensure there's a serial port mapped to SLCAN1661if (!serial_manager.have_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)) {1662serial_manager.set_protocol_and_baud(SERIALMANAGER_NUM_PORTS-1, AP_SerialManager::SerialProtocol_SLCAN, 1500000);1663}1664}1665#endif16661667canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool),1668onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, this);16691670if (user_set_node_id != CANARD_BROADCAST_NODE_ID) {1671canardSetLocalNodeID(&dronecan.canard, user_set_node_id);1672}1673}167416751676#ifdef HAL_PERIPH_ENABLE_RC_OUT1677#if HAL_WITH_ESC_TELEM1678// try to map the ESC number to a motor number. This is needed1679// for when we have multiple CAN nodes, one for each ESC1680uint8_t AP_Periph_FW::get_motor_number(const uint8_t esc_number) const1681{1682const auto *channel = SRV_Channels::srv_channel(esc_number);1683// try to map the ESC number to a motor number. This is needed1684// for when we have multiple CAN nodes, one for each ESC1685if (channel == nullptr) {1686return esc_number;1687}1688const int8_t motor_num = channel->get_motor_num();1689return (motor_num == -1) ? esc_number : motor_num;1690}16911692/*1693send ESC status packets based on AP_ESC_Telem1694*/1695void AP_Periph_FW::esc_telem_update()1696{1697uint32_t mask = esc_telem.get_active_esc_mask();1698while (mask != 0) {1699int8_t i = __builtin_ffs(mask) - 1;1700mask &= ~(1U<<i);1701const float nan = nanf("");1702uavcan_equipment_esc_Status pkt {};1703pkt.esc_index = get_motor_number(i);17041705if (!esc_telem.get_voltage(i, pkt.voltage)) {1706pkt.voltage = nan;1707}1708if (!esc_telem.get_current(i, pkt.current)) {1709pkt.current = nan;1710}1711int16_t temperature;1712if (esc_telem.get_motor_temperature(i, temperature)) {1713pkt.temperature = C_TO_KELVIN(temperature*0.01);1714} else if (esc_telem.get_temperature(i, temperature)) {1715pkt.temperature = C_TO_KELVIN(temperature*0.01);1716} else {1717pkt.temperature = nan;1718}1719float rpm;1720if (esc_telem.get_raw_rpm(i, rpm)) {1721pkt.rpm = rpm;1722}17231724#if AP_EXTENDED_ESC_TELEM_ENABLED1725uint8_t power_rating_pct;1726if (esc_telem.get_power_percentage(i, power_rating_pct)) {1727pkt.power_rating_pct = power_rating_pct;1728}1729#endif17301731pkt.error_count = 0;17321733uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];1734uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());1735canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,1736UAVCAN_EQUIPMENT_ESC_STATUS_ID,1737CANARD_TRANSFER_PRIORITY_LOW,1738&buffer[0],1739total_size);1740}1741}1742#endif // HAL_WITH_ESC_TELEM17431744#if AP_EXTENDED_ESC_TELEM_ENABLED1745void AP_Periph_FW::esc_telem_extended_update(const uint32_t &now_ms)1746{1747if (g.esc_extended_telem_rate <= 0) {1748// Not configured to send1749return;1750}17511752uint32_t mask = esc_telem.get_active_esc_mask();1753if (mask == 0) {1754// No ESCs to report1755return;1756}17571758// ESCs are sent in turn to minimise used bandwidth, to make the rate param match the status message we multiply1759// the period such that the param gives the per-esc rate1760const uint32_t update_period_ms = 1000 / constrain_int32(g.esc_extended_telem_rate.get() * __builtin_popcount(mask), 1, 1000);1761if (now_ms - last_esc_telem_extended_update < update_period_ms) {1762// Too soon!1763return;1764}1765last_esc_telem_extended_update = now_ms;17661767for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {1768// Send each ESC in turn1769const uint8_t index = (last_esc_telem_extended_sent_id + 1 + i) % ESC_TELEM_MAX_ESCS;17701771if ((mask & (1U << index)) == 0) {1772// Not enabled1773continue;1774}17751776uavcan_equipment_esc_StatusExtended pkt {};17771778// Only send if we have data1779bool have_data = false;17801781int16_t motor_temp_cdeg;1782if (esc_telem.get_motor_temperature(index, motor_temp_cdeg)) {1783// Convert from centi-degrees to degrees1784pkt.motor_temperature_degC = motor_temp_cdeg * 0.01;1785have_data = true;1786}17871788have_data |= esc_telem.get_input_duty(index, pkt.input_pct);1789have_data |= esc_telem.get_output_duty(index, pkt.output_pct);1790have_data |= esc_telem.get_flags(index, pkt.status_flags);17911792if (have_data) {1793pkt.esc_index = get_motor_number(index);17941795uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_MAX_SIZE];1796const uint16_t total_size = uavcan_equipment_esc_StatusExtended_encode(&pkt, buffer, !canfdout());17971798canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_SIGNATURE,1799UAVCAN_EQUIPMENT_ESC_STATUSEXTENDED_ID,1800CANARD_TRANSFER_PRIORITY_LOW,1801&buffer[0],1802total_size);1803}18041805last_esc_telem_extended_sent_id = index;1806break;1807}1808}1809#endif18101811#ifdef HAL_PERIPH_ENABLE_ESC_APD1812void AP_Periph_FW::apd_esc_telem_update()1813{1814for(uint8_t i = 0; i < ARRAY_SIZE(apd_esc_telem); i++) {1815if (apd_esc_telem[i] == nullptr) {1816continue;1817}1818ESC_APD_Telem &esc = *apd_esc_telem[i];18191820if (esc.update()) {1821const ESC_APD_Telem::telem &t = esc.get_telem();18221823uavcan_equipment_esc_Status pkt {};1824static_assert(APD_ESC_INSTANCES <= ARRAY_SIZE(g.esc_number), "There must be an ESC instance number for each APD ESC");1825pkt.esc_index = g.esc_number[i];1826pkt.voltage = t.voltage;1827pkt.current = t.current;1828pkt.temperature = t.temperature;1829pkt.rpm = t.rpm;1830pkt.power_rating_pct = t.power_rating_pct;1831pkt.error_count = t.error_count;18321833uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE];1834uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout());1835canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE,1836UAVCAN_EQUIPMENT_ESC_STATUS_ID,1837CANARD_TRANSFER_PRIORITY_LOW,1838&buffer[0],1839total_size);1840}1841}18421843}1844#endif // HAL_PERIPH_ENABLE_ESC_APD1845#endif // HAL_PERIPH_ENABLE_RC_OUT18461847void AP_Periph_FW::can_update()1848{1849const uint32_t now = AP_HAL::millis();1850const uint32_t led_pattern = 0xAAAA;1851const uint32_t led_change_period = 50;1852static uint8_t led_idx = 0;1853static uint32_t last_led_change;18541855if ((now - last_led_change > led_change_period) && no_iface_finished_dna) {1856// blink LED in recognisable pattern while waiting for DNA1857#ifdef HAL_GPIO_PIN_LED1858palWriteLine(HAL_GPIO_PIN_LED, (led_pattern & (1U<<led_idx))?1:0);1859#elif defined(HAL_GPIO_PIN_SAFE_LED)1860// or use safety LED if defined1861palWriteLine(HAL_GPIO_PIN_SAFE_LED, (led_pattern & (1U<<led_idx))?1:0);1862#else1863(void)led_pattern;1864(void)led_idx;1865#endif1866led_idx = (led_idx+1) % 32;1867last_led_change = now;1868}18691870if (AP_HAL::millis() > dronecan.send_next_node_id_allocation_request_at_ms) {1871can_do_dna();1872}18731874static uint32_t last_1Hz_ms;1875if (now - last_1Hz_ms >= 1000) {1876last_1Hz_ms = now;1877process1HzTasks(AP_HAL::micros64());1878}18791880#if CONFIG_HAL_BOARD == HAL_BOARD_SITL1881if (!hal.run_in_maintenance_mode())1882#endif1883{1884#ifdef HAL_PERIPH_ENABLE_MAG1885can_mag_update();1886#endif1887#ifdef HAL_PERIPH_ENABLE_GPS1888can_gps_update();1889#endif1890#if AP_UART_MONITOR_ENABLED1891send_serial_monitor_data();1892#endif1893#ifdef HAL_PERIPH_ENABLE_BATTERY1894can_battery_update();1895#endif1896#ifdef HAL_PERIPH_ENABLE_BARO1897can_baro_update();1898#endif1899#ifdef HAL_PERIPH_ENABLE_AIRSPEED1900can_airspeed_update();1901#endif1902#ifdef HAL_PERIPH_ENABLE_RANGEFINDER1903can_rangefinder_update();1904#endif1905#ifdef HAL_PERIPH_ENABLE_PROXIMITY1906can_proximity_update();1907#endif1908#if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY)1909can_buzzer_update();1910#endif1911#ifdef HAL_GPIO_PIN_SAFE_LED1912can_safety_LED_update();1913#endif1914#ifdef HAL_GPIO_PIN_SAFE_BUTTON1915can_safety_button_update();1916#endif1917#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT1918pwm_hardpoint_update();1919#endif1920#ifdef HAL_PERIPH_ENABLE_HWESC1921hwesc_telem_update();1922#endif1923#ifdef HAL_PERIPH_ENABLE_ESC_APD1924apd_esc_telem_update();1925#endif1926#ifdef HAL_PERIPH_ENABLE_MSP1927msp_sensor_update();1928#endif1929#ifdef HAL_PERIPH_ENABLE_RC_OUT1930rcout_update();1931#endif1932#ifdef HAL_PERIPH_ENABLE_EFI1933can_efi_update();1934#endif1935#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE1936temperature_sensor_update();1937#endif1938#ifdef HAL_PERIPH_ENABLE_RPM_STREAM1939rpm_sensor_send();1940#endif1941}1942const uint32_t now_us = AP_HAL::micros();1943while ((AP_HAL::micros() - now_us) < 1000) {1944hal.scheduler->delay_microseconds(HAL_PERIPH_LOOP_DELAY_US);19451946#if HAL_CANFD_SUPPORTED1947// allow for user enabling/disabling CANFD at runtime1948dronecan.canard.tao_disabled = g.can_fdmode == 1;1949#endif1950{1951WITH_SEMAPHORE(canard_broadcast_semaphore);1952processTx();1953processRx();1954#if HAL_PERIPH_CAN_MIRROR1955processMirror();1956#endif // HAL_PERIPH_CAN_MIRROR19571958}1959}19601961// if there is a reboot scheduled, do it 1 second after request to allow the acknowledgement to be sent1962if (reboot_request_ms != 0 && (AP_HAL::millis() - reboot_request_ms > 1000)) {1963prepare_reboot();1964#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS1965NVIC_SystemReset();1966#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL1967HAL_SITL::actually_reboot();1968#endif1969}1970}19711972// printf to CAN LogMessage for debugging1973void can_vprintf(uint8_t severity, const char *fmt, va_list ap)1974{1975// map MAVLink levels to CAN levels1976uint8_t level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;1977switch (severity) {1978case MAV_SEVERITY_DEBUG:1979level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG;1980break;1981case MAV_SEVERITY_INFO:1982level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_INFO;1983break;1984case MAV_SEVERITY_NOTICE:1985case MAV_SEVERITY_WARNING:1986level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_WARNING;1987break;1988case MAV_SEVERITY_ERROR:1989case MAV_SEVERITY_CRITICAL:1990case MAV_SEVERITY_ALERT:1991case MAV_SEVERITY_EMERGENCY:1992level = UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_ERROR;1993break;1994}19951996#if HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF1997const uint8_t packet_count_max = 4; // how many packets we're willing to break up an over-sized string into1998const uint8_t packet_data_max = 90; // max single debug string length = sizeof(uavcan_protocol_debug_LogMessage.text.data)1999uint8_t buffer_data[packet_count_max*packet_data_max] {};20002001// strip off any negative return errors by treating result as 02002uint32_t char_count = MAX(vsnprintf((char*)buffer_data, sizeof(buffer_data), fmt, ap), 0);20032004// send multiple uavcan_protocol_debug_LogMessage packets if the fmt string is too long.2005uint16_t buffer_offset = 0;2006for (uint8_t i=0; i<packet_count_max && char_count > 0; i++) {2007uavcan_protocol_debug_LogMessage pkt {};2008pkt.level.value = level;2009pkt.text.len = MIN(char_count, sizeof(pkt.text.data));2010char_count -= pkt.text.len;20112012memcpy(pkt.text.data, &buffer_data[buffer_offset], pkt.text.len);2013buffer_offset += pkt.text.len;20142015uint8_t buffer_packet[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];2016const uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer_packet, !periph.canfdout());20172018periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,2019UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,2020CANARD_TRANSFER_PRIORITY_LOW,2021buffer_packet,2022len);2023}20242025#else2026uavcan_protocol_debug_LogMessage pkt {};2027uint8_t buffer[UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_MAX_SIZE];2028uint32_t n = vsnprintf((char*)pkt.text.data, sizeof(pkt.text.data), fmt, ap);2029pkt.level.value = level;2030pkt.text.len = MIN(n, sizeof(pkt.text.data));20312032uint32_t len = uavcan_protocol_debug_LogMessage_encode(&pkt, buffer, !periph.canfdout());20332034periph.canard_broadcast(UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_SIGNATURE,2035UAVCAN_PROTOCOL_DEBUG_LOGMESSAGE_ID,2036CANARD_TRANSFER_PRIORITY_LOW,2037buffer,2038len);20392040#endif2041}20422043// printf to CAN LogMessage for debugging, with severity2044void can_printf_severity(uint8_t severity, const char *fmt, ...)2045{2046va_list ap;2047va_start(ap, fmt);2048can_vprintf(severity, fmt, ap);2049va_end(ap);2050}20512052// printf to CAN LogMessage for debugging, with DEBUG level2053void can_printf(const char *fmt, ...)2054{2055va_list ap;2056va_start(ap, fmt);2057can_vprintf(MAV_SEVERITY_DEBUG, fmt, ap);2058va_end(ap);2059}206020612062