Path: blob/master/libraries/AP_DroneCAN/AP_DroneCAN.cpp
9688 views
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*14* Author: Eugene Shamaev, Siddharth Bharat Purohit15*/1617#include <AP_Common/AP_Common.h>18#include <AP_HAL/AP_HAL.h>1920#if HAL_ENABLE_DRONECAN_DRIVERS21#include "AP_DroneCAN.h"22#include <GCS_MAVLink/GCS.h>2324#include <AP_BoardConfig/AP_BoardConfig.h>25#include <AP_CANManager/AP_CANManager.h>2627#include <AP_Arming/AP_Arming.h>28#include <AP_GPS/AP_GPS_DroneCAN.h>29#include <AP_Compass/AP_Compass_DroneCAN.h>30#include <AP_Baro/AP_Baro_DroneCAN.h>31#include <AP_Vehicle/AP_Vehicle.h>32#include <AP_BattMonitor/AP_BattMonitor_DroneCAN.h>33#include <AP_Airspeed/AP_Airspeed_DroneCAN.h>34#include <AP_OpticalFlow/AP_OpticalFlow_HereFlow.h>35#include <AP_RangeFinder/AP_RangeFinder_DroneCAN.h>36#include <AP_RCProtocol/AP_RCProtocol_DroneCAN.h>37#include <AP_EFI/AP_EFI_DroneCAN.h>38#include <AP_GPS/AP_GPS_DroneCAN.h>39#include <AP_GPS/AP_GPS.h>40#include <AP_BattMonitor/AP_BattMonitor_DroneCAN.h>41#include <AP_Compass/AP_Compass_DroneCAN.h>42#include <AP_Airspeed/AP_Airspeed_DroneCAN.h>43#include <AP_Proximity/AP_Proximity_DroneCAN.h>44#include <SRV_Channel/SRV_Channel.h>45#include <AP_ADSB/AP_ADSB.h>46#include "AP_DroneCAN_DNA_Server.h"47#include <AP_Logger/AP_Logger.h>48#include <AP_Notify/AP_Notify.h>49#include <AP_OpenDroneID/AP_OpenDroneID.h>50#include <AP_Mount/AP_Mount_Xacti.h>51#include <string.h>52#include <AP_Servo_Telem/AP_Servo_Telem.h>5354#if AP_DRONECAN_SERIAL_ENABLED55#include "AP_DroneCAN_serial.h"56#endif5758#if AP_RELAY_DRONECAN_ENABLED59#include <AP_Relay/AP_Relay.h>60#endif6162#include <AP_TemperatureSensor/AP_TemperatureSensor_DroneCAN.h>6364#include <AP_RPM/RPM_DroneCAN.h>6566extern const AP_HAL::HAL& hal;6768// setup default pool size69#ifndef DRONECAN_NODE_POOL_SIZE70#if HAL_CANFD_SUPPORTED71#define DRONECAN_NODE_POOL_SIZE 1638472#else73#define DRONECAN_NODE_POOL_SIZE 819274#endif75#endif7677#if HAL_CANFD_SUPPORTED78#define DRONECAN_STACK_SIZE 819279#else80#define DRONECAN_STACK_SIZE 409681#endif8283#ifndef AP_DRONECAN_DEFAULT_NODE84#define AP_DRONECAN_DEFAULT_NODE 1085#endif8687#define AP_DRONECAN_GETSET_TIMEOUT_MS 100 // timeout waiting for response from node after 0.1 sec8889#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)9091// Translation of all messages from DroneCAN structures into AP structures is done92// in AP_DroneCAN and not in corresponding drivers.93// The overhead of including definitions of DSDL is very high and it is best to94// concentrate in one place.9596// table of user settable CAN bus parameters97const AP_Param::GroupInfo AP_DroneCAN::var_info[] = {98// @Param: NODE99// @DisplayName: Own node ID100// @Description: DroneCAN node ID used by the driver itself on this network101// @Range: 1 125102// @User: Advanced103AP_GROUPINFO("NODE", 1, AP_DroneCAN, _dronecan_node, AP_DRONECAN_DEFAULT_NODE),104105// @Param: SRV_BM106// @DisplayName: Output channels to be transmitted as servo over DroneCAN107// @Description: Bitmask with one set for channel to be transmitted as a servo command over DroneCAN108// @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32109110// @User: Advanced111AP_GROUPINFO("SRV_BM", 2, AP_DroneCAN, _servo_bm, 0),112113// @Param: ESC_BM114// @DisplayName: Output channels to be transmitted as ESC over DroneCAN115// @Description: Bitmask with one set for channel to be transmitted as a ESC command over DroneCAN116// @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32117// @User: Advanced118AP_GROUPINFO("ESC_BM", 3, AP_DroneCAN, _esc_bm, 0),119120// @Param: SRV_RT121// @DisplayName: Servo output rate122// @Description: Maximum transmit rate for servo outputs123// @Range: 1 200124// @Units: Hz125// @User: Advanced126AP_GROUPINFO("SRV_RT", 4, AP_DroneCAN, _servo_rate_hz, 50),127128// @Param: OPTION129// @DisplayName: DroneCAN options130// @Description: Option flags131// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy,4:SendServoAsPWM,5:SendGNSS,6:UseHimarkServo,7:HobbyWingESC,8:EnableStats,9:EnableFlexDebug,10:SecondaryAllowExtendedFrames132// @User: Advanced133AP_GROUPINFO("OPTION", 5, AP_DroneCAN, _options, 0),134135// @Param: NTF_RT136// @DisplayName: Notify State rate137// @Description: Maximum transmit rate for Notify State Message138// @Range: 1 200139// @Units: Hz140// @User: Advanced141AP_GROUPINFO("NTF_RT", 6, AP_DroneCAN, _notify_state_hz, 20),142143// @Param: ESC_OF144// @DisplayName: ESC Output channels offset145// @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo outputs 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficient usage of CAN bandwidth146// @Range: 0 18147// @User: Advanced148AP_GROUPINFO("ESC_OF", 7, AP_DroneCAN, _esc_offset, 0),149150// @Param: POOL151// @DisplayName: CAN pool size152// @Description: Amount of memory in bytes to allocate for the DroneCAN memory pool. More memory is needed for higher CAN bus loads153// @Range: 1024 16384154// @User: Advanced155AP_GROUPINFO("POOL", 8, AP_DroneCAN, _pool_size, DRONECAN_NODE_POOL_SIZE),156157// @Param: ESC_RV158// @DisplayName: Bitmask for output channels for reversible ESCs over DroneCAN.159// @Description: Bitmask with one set for each output channel that uses a reversible ESC over DroneCAN. Reversible ESCs use both positive and negative values in RawCommands, with positive commanding the forward direction and negative commanding the reverse direction.160// @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32161// @User: Advanced162AP_GROUPINFO("ESC_RV", 9, AP_DroneCAN, _esc_rv, 0),163164#if AP_RELAY_DRONECAN_ENABLED165// @Param: RLY_RT166// @DisplayName: DroneCAN relay output rate167// @Description: Maximum transmit rate for relay outputs, note that this rate is per message each message does 1 relay, so if with more relays will take longer to update at the same rate, a extra message will be sent when a relay changes state168// @Range: 0 200169// @Units: Hz170// @User: Advanced171AP_GROUPINFO("RLY_RT", 23, AP_DroneCAN, _relay.rate_hz, 0),172#endif173174#if AP_DRONECAN_SERIAL_ENABLED175/*176due to the parameter tree depth limitation we can't use a sub-table for the serial parameters177*/178179// @Param: SER_EN180// @DisplayName: DroneCAN Serial enable181// @Description: Enable DroneCAN virtual serial ports182// @Values: 0:Disabled, 1:Enabled183// @RebootRequired: True184// @User: Advanced185AP_GROUPINFO_FLAGS("SER_EN", 10, AP_DroneCAN, serial.enable, 0, AP_PARAM_FLAG_ENABLE),186187// @Param: S1_NOD188// @DisplayName: Serial CAN remote node number189// @Description: CAN remote node number for serial port190// @Range: 0 127191// @RebootRequired: True192// @User: Advanced193AP_GROUPINFO("S1_NOD", 11, AP_DroneCAN, serial.ports[0].node, 0),194195// @Param: S1_IDX196// @DisplayName: DroneCAN Serial1 index197// @Description: Serial port number on remote CAN node198// @Range: -1 100199// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6200// @RebootRequired: True201// @User: Advanced202AP_GROUPINFO("S1_IDX", 12, AP_DroneCAN, serial.ports[0].idx, -1),203204// @Param: S1_BD205// @DisplayName: DroneCAN Serial default baud rate206// @Description: Serial baud rate on remote CAN node207// @CopyFieldsFrom: SERIAL1_BAUD208// @RebootRequired: True209// @User: Advanced210AP_GROUPINFO("S1_BD", 13, AP_DroneCAN, serial.ports[0].state.baud, 57600),211212// @Param: S1_PRO213// @DisplayName: Serial protocol of DroneCAN serial port214// @Description: Serial protocol of DroneCAN serial port215// @CopyFieldsFrom: SERIAL1_PROTOCOL216// @RebootRequired: True217// @User: Advanced218AP_GROUPINFO("S1_PRO", 14, AP_DroneCAN, serial.ports[0].state.protocol, -1),219220#if AP_DRONECAN_SERIAL_NUM_PORTS > 1221// @Param: S2_NOD222// @DisplayName: Serial CAN remote node number223// @Description: CAN remote node number for serial port224// @CopyFieldsFrom: CAN_D1_UC_S1_NOD225AP_GROUPINFO("S2_NOD", 15, AP_DroneCAN, serial.ports[1].node, 0),226227// @Param: S2_IDX228// @DisplayName: Serial port number on remote CAN node229// @Description: Serial port number on remote CAN node230// @CopyFieldsFrom: CAN_D1_UC_S1_IDX231AP_GROUPINFO("S2_IDX", 16, AP_DroneCAN, serial.ports[1].idx, -1),232233// @Param: S2_BD234// @DisplayName: DroneCAN Serial default baud rate235// @Description: Serial baud rate on remote CAN node236// @CopyFieldsFrom: CAN_D1_UC_S1_BD237AP_GROUPINFO("S2_BD", 17, AP_DroneCAN, serial.ports[1].state.baud, 57600),238239// @Param: S2_PRO240// @DisplayName: Serial protocol of DroneCAN serial port241// @Description: Serial protocol of DroneCAN serial port242// @CopyFieldsFrom: CAN_D1_UC_S1_PRO243AP_GROUPINFO("S2_PRO", 18, AP_DroneCAN, serial.ports[1].state.protocol, -1),244#endif245246#if AP_DRONECAN_SERIAL_NUM_PORTS > 2247// @Param: S3_NOD248// @DisplayName: Serial CAN remote node number249// @Description: CAN node number for serial port250// @CopyFieldsFrom: CAN_D1_UC_S1_NOD251AP_GROUPINFO("S3_NOD", 19, AP_DroneCAN, serial.ports[2].node, 0),252253// @Param: S3_IDX254// @DisplayName: Serial port number on remote CAN node255// @Description: Serial port number on remote CAN node256// @CopyFieldsFrom: CAN_D1_UC_S1_IDX257AP_GROUPINFO("S3_IDX", 20, AP_DroneCAN, serial.ports[2].idx, 0),258259// @Param: S3_BD260// @DisplayName: Serial baud rate on remote CAN node261// @Description: Serial baud rate on remote CAN node262// @CopyFieldsFrom: CAN_D1_UC_S1_BD263AP_GROUPINFO("S3_BD", 21, AP_DroneCAN, serial.ports[2].state.baud, 57600),264265// @Param: S3_PRO266// @DisplayName: Serial protocol of DroneCAN serial port267// @Description: Serial protocol of DroneCAN serial port268// @CopyFieldsFrom: CAN_D1_UC_S1_PRO269AP_GROUPINFO("S3_PRO", 22, AP_DroneCAN, serial.ports[2].state.protocol, -1),270#endif271#endif // AP_DRONECAN_SERIAL_ENABLED272273// RLY_RT is index 23 but has to be above SER_EN so its not hidden274275AP_GROUPEND276};277278// this is the timeout in milliseconds for periodic message types. We279// set this to 1 to minimise resend of stale msgs280#define CAN_PERIODIC_TX_TIMEOUT_MS 2281282AP_DroneCAN::AP_DroneCAN(const int driver_index) :283_driver_index(driver_index),284canard_iface(driver_index),285_dna_server(*this, canard_iface, driver_index)286{287AP_Param::setup_object_defaults(this, var_info);288289for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) {290_SRV_conf[i].esc_pending = false;291_SRV_conf[i].servo_pending = false;292}293294debug_dronecan(AP_CANManager::LOG_INFO, "AP_DroneCAN constructed\n\r");295}296297AP_DroneCAN::~AP_DroneCAN()298{299}300301AP_DroneCAN *AP_DroneCAN::get_dronecan(uint8_t driver_index)302{303if (driver_index >= AP::can().get_num_drivers() ||304AP::can().get_driver_type(driver_index) != AP_CAN::Protocol::DroneCAN) {305return nullptr;306}307return static_cast<AP_DroneCAN*>(AP::can().get_driver(driver_index));308}309310bool AP_DroneCAN::add_interface(AP_HAL::CANIface* can_iface)311{312if (!canard_iface.add_interface(can_iface)) {313debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: can't add DroneCAN interface\n\r");314return false;315}316return true;317}318319void AP_DroneCAN::init(uint8_t driver_index)320{321if (driver_index != _driver_index) {322debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: init called with wrong driver_index");323return;324}325if (_initialized) {326debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: init called more than once\n\r");327return;328}329uint8_t node = _dronecan_node;330if (node < 1 || node > 125) { // reset to default if invalid331_dronecan_node.set(AP_DRONECAN_DEFAULT_NODE);332node = AP_DRONECAN_DEFAULT_NODE;333}334335node_info_rsp.name.len = hal.util->snprintf((char*)node_info_rsp.name.data, sizeof(node_info_rsp.name.data), "org.ardupilot:%u", driver_index);336337node_info_rsp.software_version.major = AP_DRONECAN_SW_VERS_MAJOR;338node_info_rsp.software_version.minor = AP_DRONECAN_SW_VERS_MINOR;339node_info_rsp.hardware_version.major = AP_DRONECAN_HW_VERS_MAJOR;340node_info_rsp.hardware_version.minor = AP_DRONECAN_HW_VERS_MINOR;341342#if HAL_CANFD_SUPPORTED343if (option_is_set(Options::CANFD_ENABLED)) {344canard_iface.set_canfd(true);345}346#endif347348uint8_t uid_len = sizeof(uavcan_protocol_HardwareVersion::unique_id);349uint8_t unique_id[sizeof(uavcan_protocol_HardwareVersion::unique_id)];350351mem_pool = NEW_NOTHROW uint32_t[_pool_size/sizeof(uint32_t)];352if (mem_pool == nullptr) {353debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to allocate memory pool\n\r");354return;355}356canard_iface.init(mem_pool, (_pool_size/sizeof(uint32_t))*sizeof(uint32_t), node);357358if (!hal.util->get_system_id_unformatted(unique_id, uid_len)) {359return;360}361unique_id[uid_len - 1] += node;362memcpy(node_info_rsp.hardware_version.unique_id, unique_id, uid_len);363364//Start Servers365if (!_dna_server.init(unique_id, uid_len, node)) {366debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: Failed to start DNA Server\n\r");367return;368}369370// Roundup all subscribers from supported drivers371bool subscribed = true;372#if AP_GPS_DRONECAN_ENABLED373subscribed = subscribed && AP_GPS_DroneCAN::subscribe_msgs(this);374#endif375#if AP_COMPASS_DRONECAN_ENABLED376subscribed = subscribed && AP_Compass_DroneCAN::subscribe_msgs(this);377#endif378#if AP_BARO_DRONECAN_ENABLED379subscribed = subscribed && AP_Baro_DroneCAN::subscribe_msgs(this);380#endif381subscribed = subscribed && AP_BattMonitor_DroneCAN::subscribe_msgs(this);382#if AP_AIRSPEED_DRONECAN_ENABLED383subscribed = subscribed && AP_Airspeed_DroneCAN::subscribe_msgs(this);384#endif385#if AP_OPTICALFLOW_HEREFLOW_ENABLED386subscribed = subscribed && AP_OpticalFlow_HereFlow::subscribe_msgs(this);387#endif388#if AP_RANGEFINDER_DRONECAN_ENABLED389subscribed = subscribed && AP_RangeFinder_DroneCAN::subscribe_msgs(this);390#endif391#if AP_RCPROTOCOL_DRONECAN_ENABLED392subscribed = subscribed && AP_RCProtocol_DroneCAN::subscribe_msgs(this);393#endif394#if AP_EFI_DRONECAN_ENABLED395subscribed = subscribed && AP_EFI_DroneCAN::subscribe_msgs(this);396#endif397398#if AP_PROXIMITY_DRONECAN_ENABLED399subscribed = subscribed && AP_Proximity_DroneCAN::subscribe_msgs(this);400#endif401#if HAL_MOUNT_XACTI_ENABLED402subscribed = subscribed && AP_Mount_Xacti::subscribe_msgs(this);403#endif404#if AP_TEMPERATURE_SENSOR_DRONECAN_ENABLED405subscribed = subscribed && AP_TemperatureSensor_DroneCAN::subscribe_msgs(this);406#endif407#if AP_RPM_DRONECAN_ENABLED408subscribed = subscribed && AP_RPM_DroneCAN::subscribe_msgs(this);409#endif410411if (!subscribed) {412AP_BoardConfig::allocation_error("DroneCAN callback");413}414415act_out_array.set_timeout_ms(5);416act_out_array.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);417418esc_raw.set_timeout_ms(2);419// esc_raw is one higher than high priority to ensure that it is given higher priority over act_out_array420esc_raw.set_priority(CANARD_TRANSFER_PRIORITY_HIGH - 1);421422#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT423esc_hobbywing_raw.set_timeout_ms(2);424esc_hobbywing_raw.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);425#endif426427#if AP_DRONECAN_HIMARK_SERVO_SUPPORT428himark_out.set_timeout_ms(2);429himark_out.set_priority(CANARD_TRANSFER_PRIORITY_HIGH);430#endif431432rgb_led.set_timeout_ms(20);433rgb_led.set_priority(CANARD_TRANSFER_PRIORITY_LOW);434435buzzer.set_timeout_ms(20);436buzzer.set_priority(CANARD_TRANSFER_PRIORITY_LOW);437438safety_state.set_timeout_ms(20);439safety_state.set_priority(CANARD_TRANSFER_PRIORITY_LOW);440441arming_status.set_timeout_ms(20);442arming_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW);443444#if AP_DRONECAN_SEND_GPS445gnss_fix2.set_timeout_ms(20);446gnss_fix2.set_priority(CANARD_TRANSFER_PRIORITY_LOW);447448gnss_auxiliary.set_timeout_ms(20);449gnss_auxiliary.set_priority(CANARD_TRANSFER_PRIORITY_LOW);450451gnss_heading.set_timeout_ms(20);452gnss_heading.set_priority(CANARD_TRANSFER_PRIORITY_LOW);453454gnss_status.set_timeout_ms(20);455gnss_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW);456#endif457458rtcm_stream.set_timeout_ms(20);459rtcm_stream.set_priority(CANARD_TRANSFER_PRIORITY_LOW);460461notify_state.set_timeout_ms(20);462notify_state.set_priority(CANARD_TRANSFER_PRIORITY_LOW);463464#if HAL_MOUNT_XACTI_ENABLED465xacti_copter_att_status.set_timeout_ms(20);466xacti_copter_att_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW);467xacti_gimbal_control_data.set_timeout_ms(20);468xacti_gimbal_control_data.set_priority(CANARD_TRANSFER_PRIORITY_LOW);469xacti_gnss_status.set_timeout_ms(20);470xacti_gnss_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW);471#endif472473#if AP_RELAY_DRONECAN_ENABLED474relay_hardpoint.set_timeout_ms(20);475relay_hardpoint.set_priority(CANARD_TRANSFER_PRIORITY_LOW);476#endif477478param_save_client.set_timeout_ms(20);479param_save_client.set_priority(CANARD_TRANSFER_PRIORITY_LOW);480481param_get_set_client.set_timeout_ms(20);482param_get_set_client.set_priority(CANARD_TRANSFER_PRIORITY_LOW);483484node_status.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST);485node_status.set_timeout_ms(1000);486487protocol_stats.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST);488protocol_stats.set_timeout_ms(3000);489490can_stats.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST);491can_stats.set_timeout_ms(3000);492493node_info_server.set_timeout_ms(20);494495// setup node status496node_status_msg.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK;497node_status_msg.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_OPERATIONAL;498node_status_msg.sub_mode = 0;499500// Spin node for device discovery501for (uint8_t i = 0; i < 5; i++) {502send_node_status();503canard_iface.process(1000);504}505506hal.util->snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index);507508if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_DroneCAN::loop, void), _thread_name, DRONECAN_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_CAN, 0)) {509debug_dronecan(AP_CANManager::LOG_ERROR, "DroneCAN: couldn't create thread\n\r");510return;511}512513#if AP_DRONECAN_SERIAL_ENABLED514serial.init(this);515#endif516517_initialized = true;518debug_dronecan(AP_CANManager::LOG_INFO, "DroneCAN: init done\n\r");519}520521void AP_DroneCAN::loop(void)522{523while (true) {524if (!_initialized) {525hal.scheduler->delay_microseconds(1000);526continue;527}528529// ensure that the DroneCAN thread cannot completely saturate530// the CPU, preventing low priority threads from running531hal.scheduler->delay_microseconds(100);532533canard_iface.process(1);534535safety_state_send();536notify_state_send();537check_parameter_callback_timeout();538send_parameter_request();539send_parameter_save_request();540send_node_status();541_dna_server.verify_nodes();542543#if AP_DRONECAN_SEND_GPS && AP_GPS_DRONECAN_ENABLED544if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_DroneCAN::instance_exists(this)) {545// send if enabled and this interface/driver is not used by the AP_GPS driver546gnss_send_fix();547gnss_send_yaw();548}549#endif550logging();551#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT552hobbywing_ESC_update();553#endif554if (_SRV_armed_mask != 0) {555// we have active servos556uint32_t now = AP_HAL::micros();557const uint32_t servo_period_us = 1000000UL / unsigned(_servo_rate_hz.get());558if (now - _SRV_last_send_us >= servo_period_us) {559_SRV_last_send_us = now;560#if AP_DRONECAN_HIMARK_SERVO_SUPPORT561if (option_is_set(Options::USE_HIMARK_SERVO)) {562SRV_send_himark();563} else564#endif565{566SRV_send_actuator();567}568for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) {569_SRV_conf[i].servo_pending = false;570}571}572}573574#if AP_DRONECAN_SERIAL_ENABLED575serial.update();576#endif577578#if AP_RELAY_DRONECAN_ENABLED579relay_hardpoint_send();580#endif581}582}583584#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT585void AP_DroneCAN::hobbywing_ESC_update(void)586{587if (hal.util->get_soft_armed()) {588// don't update ID database while armed, as it can cause589// some hobbywing ESCs to stutter590return;591}592uint32_t now = AP_HAL::millis();593if (now - hobbywing.last_GetId_send_ms >= 1000U) {594hobbywing.last_GetId_send_ms = now;595com_hobbywing_esc_GetEscID msg;596msg.payload.len = 1;597msg.payload.data[0] = 0;598esc_hobbywing_GetEscID.broadcast(msg);599}600}601602/*603handle hobbywing GetEscID reply. This gets us the mapping between CAN NodeID and throttle channel604*/605void AP_DroneCAN::handle_hobbywing_GetEscID(const CanardRxTransfer& transfer, const com_hobbywing_esc_GetEscID& msg)606{607if (msg.payload.len == 2 &&608msg.payload.data[0] == transfer.source_node_id) {609// throttle channel is 2nd payload byte610const uint8_t thr_channel = msg.payload.data[1];611if (thr_channel > 0 && thr_channel <= HOBBYWING_MAX_ESC) {612hobbywing.thr_chan[thr_channel-1] = transfer.source_node_id;613}614}615}616617/*618find the ESC index given a CAN node ID619*/620bool AP_DroneCAN::hobbywing_find_esc_index(uint8_t node_id, uint8_t &esc_index) const621{622for (uint8_t i=0; i<HOBBYWING_MAX_ESC; i++) {623if (hobbywing.thr_chan[i] == node_id) {624const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER);625esc_index = i + esc_offset;626return true;627}628}629return false;630}631632/*633handle hobbywing StatusMsg1 reply634*/635void AP_DroneCAN::handle_hobbywing_StatusMsg1(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg1& msg)636{637uint8_t esc_index;638if (hobbywing_find_esc_index(transfer.source_node_id, esc_index)) {639update_rpm(esc_index, msg.rpm);640}641}642643/*644handle hobbywing StatusMsg2 reply645*/646void AP_DroneCAN::handle_hobbywing_StatusMsg2(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg2& msg)647{648uint8_t esc_index;649if (hobbywing_find_esc_index(transfer.source_node_id, esc_index)) {650TelemetryData t {651.temperature_cdeg = int16_t(msg.temperature*100),652.voltage = msg.input_voltage*0.1f,653.current = msg.current*0.1f,654};655update_telem_data(esc_index, t,656AP_ESC_Telem_Backend::TelemetryType::CURRENT|657AP_ESC_Telem_Backend::TelemetryType::VOLTAGE|658AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);659}660661}662#endif // AP_DRONECAN_HOBBYWING_ESC_SUPPORT663664void AP_DroneCAN::send_node_status(void)665{666const uint32_t now = AP_HAL::millis();667if (now - _node_status_last_send_ms < 1000) {668return;669}670_node_status_last_send_ms = now;671node_status_msg.uptime_sec = now / 1000;672node_status.broadcast(node_status_msg);673674if (option_is_set(Options::ENABLE_STATS)) {675// also send protocol and can stats676protocol_stats.broadcast(canard_iface.protocol_stats);677678// get can stats679for (uint8_t i=0; i<canard_iface.num_ifaces; i++) {680if (canard_iface.ifaces[i] == nullptr) {681continue;682}683auto* iface = hal.can[0];684for (uint8_t j=0; j<HAL_NUM_CAN_IFACES; j++) {685if (hal.can[j] == canard_iface.ifaces[i]) {686iface = hal.can[j];687break;688}689}690auto* bus_stats = iface->get_statistics();691if (bus_stats == nullptr) {692continue;693}694dronecan_protocol_CanStats can_stats_msg;695can_stats_msg.interface = i;696can_stats_msg.tx_requests = bus_stats->tx_requests;697can_stats_msg.tx_rejected = bus_stats->tx_rejected;698can_stats_msg.tx_overflow = bus_stats->tx_overflow;699can_stats_msg.tx_success = bus_stats->tx_success;700can_stats_msg.tx_timedout = bus_stats->tx_timedout;701can_stats_msg.tx_abort = bus_stats->tx_abort;702can_stats_msg.rx_received = bus_stats->rx_received;703can_stats_msg.rx_overflow = bus_stats->rx_overflow;704can_stats_msg.rx_errors = bus_stats->rx_errors;705can_stats_msg.busoff_errors = bus_stats->num_busoff_err;706can_stats.broadcast(can_stats_msg);707}708}709}710711void AP_DroneCAN::handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req)712{713node_info_rsp.status = node_status_msg;714node_info_rsp.status.uptime_sec = AP_HAL::millis() / 1000;715716node_info_server.respond(transfer, node_info_rsp);717}718719int16_t AP_DroneCAN::scale_esc_output(uint8_t idx){720static const int16_t cmd_max = ((1<<13)-1);721float scaled = hal.rcout->scale_esc_to_unity(_SRV_conf[idx].pulse);722// Prevent invalid values (from misconfigured scaling parameters) from sending non-zero commands723if (!isfinite(scaled)) {724return 0;725}726scaled = constrain_float(scaled, -1, 1);727//Check if this channel has a reversible ESC. If it does, we can send negative commands.728if ((((uint32_t) 1) << idx) & _esc_rv) {729scaled *= cmd_max;730} else {731scaled = cmd_max * (scaled + 1.0) / 2.0;732}733734return static_cast<int16_t>(scaled);735}736737///// SRV output /////738739void AP_DroneCAN::SRV_send_actuator(void)740{741uint8_t starting_servo = 0;742bool repeat_send;743744WITH_SEMAPHORE(SRV_sem);745746do {747repeat_send = false;748uavcan_equipment_actuator_ArrayCommand msg;749750uint8_t i;751// DroneCAN can hold maximum of 15 commands in one frame752for (i = 0; starting_servo < DRONECAN_SRV_NUMBER && i < 15; starting_servo++) {753uavcan_equipment_actuator_Command cmd;754755/*756* Servo output uses a range of 1000-2000 PWM for scaling.757* This converts output PWM from [1000:2000] range to [-1:1] range that758* is passed to servo as unitless type via DroneCAN.759* This approach allows for MIN/TRIM/MAX values to be used fully on760* autopilot side and for servo it should have the setup to provide maximum761* physically possible throws at [-1:1] limits.762*/763764if (_SRV_conf[starting_servo].servo_pending && ((((uint32_t) 1) << starting_servo) & _SRV_armed_mask)) {765cmd.actuator_id = starting_servo + 1;766767if (option_is_set(Options::USE_ACTUATOR_PWM)) {768cmd.command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM;769cmd.command_value = _SRV_conf[starting_servo].pulse;770} else {771cmd.command_type = UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS;772cmd.command_value = constrain_float(((float) _SRV_conf[starting_servo].pulse - 1000.0) / 500.0 - 1.0, -1.0, 1.0);773}774775msg.commands.data[i] = cmd;776777i++;778}779}780msg.commands.len = i;781if (i > 0) {782if (act_out_array.broadcast(msg) > 0) {783_srv_send_count++;784} else {785_fail_send_count++;786}787788if (i == 15) {789repeat_send = true;790}791}792} while (repeat_send);793}794795#if AP_DRONECAN_HIMARK_SERVO_SUPPORT796/*797Himark servo output. This uses com.himark.servo.ServoCmd packets798*/799void AP_DroneCAN::SRV_send_himark(void)800{801WITH_SEMAPHORE(SRV_sem);802803// ServoCmd can hold maximum of 17 commands. First find the highest pending servo < 17804int8_t highest_to_send = -1;805for (int8_t i = 16; i >= 0; i--) {806if (_SRV_conf[i].servo_pending && ((1U<<i) & _SRV_armed_mask) != 0) {807highest_to_send = i;808break;809}810}811if (highest_to_send == -1) {812// nothing to send813return;814}815com_himark_servo_ServoCmd msg {};816817for (uint8_t i = 0; i <= highest_to_send; i++) {818if ((1U<<i) & _SRV_armed_mask) {819const uint16_t pulse = constrain_int16(_SRV_conf[i].pulse - 1000, 0, 1000);820msg.cmd.data[i] = pulse;821}822}823msg.cmd.len = highest_to_send+1;824825himark_out.broadcast(msg);826}827#endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT828829void AP_DroneCAN::SRV_send_esc(void)830{831uavcan_equipment_esc_RawCommand esc_msg;832833uint8_t active_esc_num = 0, max_esc_num = 0;834uint8_t k = 0;835836// esc offset allows for efficient packing of higher ESC numbers in RawCommand837const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER);838839// find out how many esc we have enabled and if they are active at all840for (uint8_t i = esc_offset; i < DRONECAN_SRV_NUMBER; i++) {841if ((((uint32_t) 1) << i) & _ESC_armed_mask) {842max_esc_num = i + 1;843if (_SRV_conf[i].esc_pending) {844active_esc_num++;845}846}847}848849// if at least one is active (update) we need to send to all850if (active_esc_num > 0) {851k = 0;852const bool armed = hal.util->get_soft_armed();853for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) {854if (armed && ((((uint32_t) 1U) << i) & _ESC_armed_mask)) {855esc_msg.cmd.data[k] = scale_esc_output(i);856} else {857esc_msg.cmd.data[k] = static_cast<unsigned>(0);858}859860k++;861}862esc_msg.cmd.len = k;863864if (esc_raw.broadcast(esc_msg)) {865_esc_send_count++;866} else {867_fail_send_count++;868}869// immediately push data to CAN bus870canard_iface.processTx(true);871}872873for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) {874_SRV_conf[i].esc_pending = false;875}876}877878#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT879/*880support for Hobbywing DroneCAN ESCs881*/882void AP_DroneCAN::SRV_send_esc_hobbywing(void)883{884com_hobbywing_esc_RawCommand esc_msg;885886uint8_t active_esc_num = 0, max_esc_num = 0;887uint8_t k = 0;888889// esc offset allows for efficient packing of higher ESC numbers in RawCommand890const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER);891892// find out how many esc we have enabled and if they are active at all893for (uint8_t i = esc_offset; i < DRONECAN_SRV_NUMBER; i++) {894if ((((uint32_t) 1) << i) & _ESC_armed_mask) {895max_esc_num = i + 1;896if (_SRV_conf[i].esc_pending) {897active_esc_num++;898}899}900}901902// if at least one is active (update) we need to send to all903if (active_esc_num > 0) {904k = 0;905const bool armed = hal.util->get_soft_armed();906for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) {907if (armed && ((((uint32_t) 1U) << i) & _ESC_armed_mask)) {908esc_msg.command.data[k] = scale_esc_output(i);909} else {910esc_msg.command.data[k] = static_cast<unsigned>(0);911}912913k++;914}915esc_msg.command.len = k;916917if (esc_hobbywing_raw.broadcast(esc_msg)) {918_esc_send_count++;919} else {920_fail_send_count++;921}922// immediately push data to CAN bus923canard_iface.processTx(true);924}925}926#endif // AP_DRONECAN_HOBBYWING_ESC_SUPPORT927928void AP_DroneCAN::SRV_push_servos()929{930WITH_SEMAPHORE(SRV_sem);931932uint32_t non_zero_channels = 0;933for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) {934// Check if this channels has any function assigned935if (SRV_Channels::channel_function(i) >= SRV_Channel::k_none) {936_SRV_conf[i].pulse = SRV_Channels::srv_channel(i)->get_output_pwm();937_SRV_conf[i].esc_pending = true;938_SRV_conf[i].servo_pending = true;939940// Flag channels which are non zero941if (_SRV_conf[i].pulse > 0) {942non_zero_channels |= 1U << i;943}944}945}946947uint32_t servo_armed_mask = _servo_bm & non_zero_channels;948uint32_t esc_armed_mask = _esc_bm & non_zero_channels;949const bool safety_off = hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED;950if (!safety_off) {951AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();952if (boardconfig != nullptr) {953const uint32_t safety_mask = boardconfig->get_safety_mask();954servo_armed_mask &= safety_mask;955esc_armed_mask &= safety_mask;956} else {957servo_armed_mask = 0;958esc_armed_mask = 0;959}960}961_SRV_armed_mask = servo_armed_mask;962_ESC_armed_mask = esc_armed_mask;963964if (_ESC_armed_mask != 0) {965// push ESCs as fast as we can966#if AP_DRONECAN_HOBBYWING_ESC_SUPPORT967if (option_is_set(Options::USE_HOBBYWING_ESC)) {968SRV_send_esc_hobbywing();969} else970#endif971{972SRV_send_esc();973}974}975}976977// notify state send978void AP_DroneCAN::notify_state_send()979{980uint32_t now = AP_HAL::millis();981982if (_notify_state_hz == 0 || (now - _last_notify_state_ms) < uint32_t(1000 / _notify_state_hz)) {983return;984}985986ardupilot_indication_NotifyState msg;987msg.vehicle_state = 0;988if (AP_Notify::flags.initialising) {989msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_INITIALISING;990}991if (AP_Notify::flags.armed) {992msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ARMED;993}994if (AP_Notify::flags.flying) {995msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FLYING;996}997if (AP_Notify::flags.compass_cal_running) {998msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_MAGCAL_RUN;999}1000if (AP_Notify::flags.ekf_bad) {1001msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_EKF_BAD;1002}1003if (AP_Notify::flags.esc_calibration) {1004msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_ESC_CALIBRATION;1005}1006if (AP_Notify::flags.failsafe_battery) {1007msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_BATT;1008}1009if (AP_Notify::flags.failsafe_gcs) {1010msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_GCS;1011}1012if (AP_Notify::flags.failsafe_radio) {1013msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FAILSAFE_RADIO;1014}1015if (AP_Notify::flags.firmware_update) {1016msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_FW_UPDATE;1017}1018if (AP_Notify::flags.gps_fusion) {1019msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_FUSION;1020}1021if (AP_Notify::flags.gps_glitching) {1022msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_GPS_GLITCH;1023}1024if (AP_Notify::flags.have_pos_abs) {1025msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POS_ABS_AVAIL;1026}1027if (AP_Notify::flags.leak_detected) {1028msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LEAK_DET;1029}1030if (AP_Notify::flags.parachute_release) {1031msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_CHUTE_RELEASED;1032}1033if (AP_Notify::flags.powering_off) {1034msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_POWERING_OFF;1035}1036if (AP_Notify::flags.pre_arm_check) {1037msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM;1038}1039if (AP_Notify::flags.pre_arm_gps_check) {1040msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_PREARM_GPS;1041}1042if (AP_Notify::flags.save_trim) {1043msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_SAVE_TRIM;1044}1045if (AP_Notify::flags.vehicle_lost) {1046msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_LOST;1047}1048if (AP_Notify::flags.video_recording) {1049msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_VIDEO_RECORDING;1050}1051if (AP_Notify::flags.waiting_for_throw) {1052msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_THROW_READY;1053}10541055#ifndef HAL_BUILD_AP_PERIPH1056const AP_Vehicle* vehicle = AP::vehicle();1057if (vehicle != nullptr) {1058if (vehicle->is_landing()) {1059msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_IS_LANDING;1060}1061if (vehicle->is_taking_off()) {1062msg.vehicle_state |= 1 << ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_STATE_IS_TAKING_OFF;1063}1064}1065#endif // HAL_BUILD_AP_PERIPH10661067// beware that1068// ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES1069// is strange; it's number of degrees *counter-clockwise* from North.1070msg.aux_data_type = ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES;1071uint16_t yaw_cd = (uint16_t)(360.0f - AP::ahrs().get_yaw_deg())*100.0f;1072const uint8_t *data = (uint8_t *)&yaw_cd;1073for (uint8_t i=0; i<2; i++) {1074msg.aux_data.data[i] = data[i];1075}1076msg.aux_data.len = 2;1077notify_state.broadcast(msg);1078_last_notify_state_ms = AP_HAL::millis();1079}10801081#if AP_DRONECAN_SEND_GPS1082void AP_DroneCAN::gnss_send_fix()1083{1084const AP_GPS &gps = AP::gps();10851086const uint32_t gps_lib_time_ms = gps.last_message_time_ms();1087if (_gnss.last_gps_lib_fix_ms == gps_lib_time_ms) {1088return;1089}1090_gnss.last_gps_lib_fix_ms = gps_lib_time_ms;10911092/*1093send Fix2 packet1094*/10951096uavcan_equipment_gnss_Fix2 pkt {};1097const Location &loc = gps.location();1098const Vector3f &vel = gps.velocity();10991100pkt.timestamp.usec = AP_HAL::micros64();1101pkt.gnss_timestamp.usec = gps.time_epoch_usec();1102if (pkt.gnss_timestamp.usec == 0) {1103pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_NONE;1104} else {1105pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_UTC;1106}1107pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL;1108pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL;1109pkt.height_ellipsoid_mm = loc.alt * 10;1110pkt.height_msl_mm = loc.alt * 10;1111for (uint8_t i=0; i<3; i++) {1112pkt.ned_velocity[i] = vel[i];1113}1114pkt.sats_used = gps.num_sats();1115switch (gps.status()) {1116case AP_GPS::GPS_Status::NO_GPS:1117case AP_GPS::GPS_Status::NO_FIX:1118pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX;1119pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE;1120pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER;1121break;1122case AP_GPS::GPS_Status::GPS_OK_FIX_2D:1123pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX;1124pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE;1125pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER;1126break;1127case AP_GPS::GPS_Status::GPS_OK_FIX_3D:1128pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX;1129pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE;1130pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER;1131break;1132case AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS:1133pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX;1134pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS;1135pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_SBAS;1136break;1137case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT:1138pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX;1139pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK;1140pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT;1141break;1142case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED:1143pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX;1144pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK;1145pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED;1146break;1147}11481149pkt.covariance.len = 6;1150float hacc;1151if (gps.horizontal_accuracy(hacc)) {1152pkt.covariance.data[0] = pkt.covariance.data[1] = sq(hacc);1153}1154float vacc;1155if (gps.vertical_accuracy(vacc)) {1156pkt.covariance.data[2] = sq(vacc);1157}1158float sacc;1159if (gps.speed_accuracy(sacc)) {1160const float vc3 = sq(sacc);1161pkt.covariance.data[3] = pkt.covariance.data[4] = pkt.covariance.data[5] = vc3;1162}11631164gnss_fix2.broadcast(pkt);1165116611671168const uint32_t now_ms = AP_HAL::millis();1169if (now_ms - _gnss.last_send_status_ms >= 1000) {1170_gnss.last_send_status_ms = now_ms;11711172/*1173send aux packet1174*/1175uavcan_equipment_gnss_Auxiliary pkt_auxiliary {};1176pkt_auxiliary.hdop = gps.get_hdop() * 0.01;1177pkt_auxiliary.vdop = gps.get_vdop() * 0.01;11781179gnss_auxiliary.broadcast(pkt_auxiliary);118011811182/*1183send Status packet1184*/1185ardupilot_gnss_Status pkt_status {};1186pkt_status.healthy = gps.is_healthy();1187if (gps.logging_present() && gps.logging_enabled() && !gps.logging_failed()) {1188pkt_status.status |= ARDUPILOT_GNSS_STATUS_STATUS_LOGGING;1189}1190uint8_t idx; // unused1191if (pkt_status.healthy && !gps.first_unconfigured_gps(idx)) {1192pkt_status.status |= ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE;1193}11941195uint32_t error_codes;1196if (gps.get_error_codes(error_codes)) {1197pkt_status.error_codes = error_codes;1198}11991200gnss_status.broadcast(pkt_status);1201}1202}12031204void AP_DroneCAN::gnss_send_yaw()1205{1206const AP_GPS &gps = AP::gps();12071208if (!gps.have_gps_yaw()) {1209return;1210}12111212float yaw_deg, yaw_acc_deg;1213uint32_t yaw_time_ms;1214if (!gps.gps_yaw_deg(yaw_deg, yaw_acc_deg, yaw_time_ms) && yaw_time_ms != _gnss.last_lib_yaw_time_ms) {1215return;1216}12171218_gnss.last_lib_yaw_time_ms = yaw_time_ms;12191220ardupilot_gnss_Heading pkt_heading {};1221pkt_heading.heading_valid = true;1222pkt_heading.heading_accuracy_valid = is_positive(yaw_acc_deg);1223pkt_heading.heading_rad = radians(yaw_deg);1224pkt_heading.heading_accuracy_rad = radians(yaw_acc_deg);12251226gnss_heading.broadcast(pkt_heading);1227}1228#endif // AP_DRONECAN_SEND_GPS12291230// SafetyState send1231void AP_DroneCAN::safety_state_send()1232{1233uint32_t now = AP_HAL::millis();1234if (now - _last_safety_state_ms < 500) {1235// update at 2Hz1236return;1237}1238_last_safety_state_ms = now;12391240{ // handle SafetyState1241ardupilot_indication_SafetyState safety_msg;1242auto state = hal.util->safety_switch_state();1243if (_SRV_armed_mask != 0 || _ESC_armed_mask != 0) {1244// if we are outputting any servos or ESCs due to1245// BRD_SAFETY_MASK then we need to advertise safety as1246// off, this changes LEDs to indicate unsafe and allows1247// AP_Periph ESCs and servos to run1248state = AP_HAL::Util::SAFETY_ARMED;1249}1250switch (state) {1251case AP_HAL::Util::SAFETY_ARMED:1252safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_OFF;1253safety_state.broadcast(safety_msg);1254break;1255case AP_HAL::Util::SAFETY_DISARMED:1256safety_msg.status = ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON;1257safety_state.broadcast(safety_msg);1258break;1259default:1260// nothing to send1261break;1262}1263}12641265{ // handle ArmingStatus1266uavcan_equipment_safety_ArmingStatus arming_msg;1267arming_msg.status = hal.util->get_soft_armed() ? UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED :1268UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_DISARMED;1269arming_status.broadcast(arming_msg);1270}1271}12721273// Send relay outputs with hardpoint msg1274#if AP_RELAY_DRONECAN_ENABLED1275void AP_DroneCAN::relay_hardpoint_send()1276{1277const uint32_t now = AP_HAL::millis();1278if ((_relay.rate_hz == 0) || ((now - _relay.last_send_ms) < uint32_t(1000 / _relay.rate_hz))) {1279// Rate limit per user config1280return;1281}1282_relay.last_send_ms = now;12831284AP_Relay *relay = AP::relay();1285if (relay == nullptr) {1286return;1287}12881289uavcan_equipment_hardpoint_Command msg {};12901291// Relay will populate the next command to send and update the last index1292// This will cycle through each relay in turn1293if (relay->dronecan.populate_next_command(_relay.last_index, msg)) {1294relay_hardpoint.broadcast(msg);1295}12961297}1298#endif // AP_RELAY_DRONECAN_ENABLED12991300/*1301handle Button message1302*/1303void AP_DroneCAN::handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg)1304{1305switch (msg.button) {1306case ARDUPILOT_INDICATION_BUTTON_BUTTON_SAFETY: {1307AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();1308if (brdconfig && brdconfig->safety_button_handle_pressed(msg.press_time)) {1309AP_HAL::Util::safety_state state = hal.util->safety_switch_state();1310if (state == AP_HAL::Util::SAFETY_ARMED) {1311hal.rcout->force_safety_on();1312} else {1313hal.rcout->force_safety_off();1314}1315}1316break;1317}1318}1319}13201321/*1322handle traffic report1323*/1324void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg)1325{1326#if HAL_ADSB_ENABLED1327AP_ADSB *adsb = AP::ADSB();1328if (!adsb || !adsb->enabled()) {1329// ADSB not enabled1330return;1331}13321333AP_ADSB::adsb_vehicle_t vehicle;1334mavlink_adsb_vehicle_t &pkt = vehicle.info;13351336pkt.ICAO_address = msg.icao_address;1337pkt.tslc = msg.tslc;1338pkt.lat = msg.latitude_deg_1e7;1339pkt.lon = msg.longitude_deg_1e7;1340pkt.altitude = msg.alt_m * 1000;1341pkt.heading = degrees(msg.heading) * 100;1342pkt.hor_velocity = norm(msg.velocity[0], msg.velocity[1]) * 100;1343pkt.ver_velocity = -msg.velocity[2] * 100;1344pkt.squawk = msg.squawk;1345for (uint8_t i=0; i<9; i++) {1346pkt.callsign[i] = msg.callsign[i];1347}1348pkt.emitter_type = msg.traffic_type;13491350if (msg.alt_type == ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_PRESSURE_AMSL) {1351pkt.flags |= ADSB_FLAGS_VALID_ALTITUDE;1352pkt.altitude_type = ADSB_ALTITUDE_TYPE_PRESSURE_QNH;1353} else if (msg.alt_type == ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ALT_TYPE_WGS84) {1354pkt.flags |= ADSB_FLAGS_VALID_ALTITUDE;1355pkt.altitude_type = ADSB_ALTITUDE_TYPE_GEOMETRIC;1356}13571358if (msg.lat_lon_valid) {1359pkt.flags |= ADSB_FLAGS_VALID_COORDS;1360}1361if (msg.heading_valid) {1362pkt.flags |= ADSB_FLAGS_VALID_HEADING;1363}1364if (msg.velocity_valid) {1365pkt.flags |= ADSB_FLAGS_VALID_VELOCITY;1366}1367if (msg.callsign_valid) {1368pkt.flags |= ADSB_FLAGS_VALID_CALLSIGN;1369}1370if (msg.ident_valid) {1371pkt.flags |= ADSB_FLAGS_VALID_SQUAWK;1372}1373if (msg.simulated_report) {1374pkt.flags |= ADSB_FLAGS_SIMULATED;1375}1376if (msg.vertical_velocity_valid) {1377pkt.flags |= ADSB_FLAGS_VERTICAL_VELOCITY_VALID;1378}1379if (msg.baro_valid) {1380pkt.flags |= ADSB_FLAGS_BARO_VALID;1381}13821383vehicle.last_update_ms = AP_HAL::millis() - (vehicle.info.tslc * 1000);1384adsb->handle_adsb_vehicle(vehicle);1385#endif1386}13871388/*1389handle actuator status message1390*/1391#if AP_SERVO_TELEM_ENABLED1392void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg)1393{1394AP_Servo_Telem *servo_telem = AP_Servo_Telem::get_singleton();1395if (servo_telem == nullptr) {1396return;1397}13981399const AP_Servo_Telem::TelemetryData telem_data {1400.measured_position = degrees(msg.position),1401.force = msg.force,1402.speed = msg.speed,1403.duty_cycle = msg.power_rating_pct,1404.present_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |1405AP_Servo_Telem::TelemetryData::Types::FORCE |1406AP_Servo_Telem::TelemetryData::Types::SPEED |1407AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE1408};14091410servo_telem->update_telem_data(msg.actuator_id, telem_data);1411}1412#endif14131414#if AP_DRONECAN_HIMARK_SERVO_SUPPORT && AP_SERVO_TELEM_ENABLED1415/*1416handle himark ServoInfo message1417*/1418void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg)1419{1420AP_Servo_Telem *servo_telem = AP_Servo_Telem::get_singleton();1421if (servo_telem == nullptr) {1422return;1423}14241425const AP_Servo_Telem::TelemetryData telem_data {1426.command_position = msg.pos_cmd * 0.01,1427.measured_position = msg.pos_sensor * 0.01,1428.voltage = msg.voltage * 0.01,1429.current = msg.current * 0.01,1430.motor_temperature_cdeg = int16_t(((msg.motor_temp * 0.2) - 40) * 100),1431.pcb_temperature_cdeg = int16_t(((msg.pcb_temp * 0.2) - 40) * 100),1432.status_flags = msg.error_status,1433.present_types = AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION |1434AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |1435AP_Servo_Telem::TelemetryData::Types::VOLTAGE |1436AP_Servo_Telem::TelemetryData::Types::CURRENT |1437AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP |1438AP_Servo_Telem::TelemetryData::Types::PCB_TEMP |1439AP_Servo_Telem::TelemetryData::Types::STATUS1440};14411442servo_telem->update_telem_data(msg.servo_id, telem_data);1443}1444#endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT14451446#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED1447void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg)1448{1449AP_Servo_Telem *servo_telem = AP_Servo_Telem::get_singleton();1450if (servo_telem == nullptr) {1451return;1452}14531454const AP_Servo_Telem::TelemetryData telem_data {1455.measured_position = degrees(msg.actual_position),1456.voltage = msg.voltage * 0.2,1457.current = msg.current * 0.025,1458.duty_cycle = uint8_t(msg.motor_pwm * (100.0/255.0)),1459.motor_temperature_cdeg = int16_t((msg.motor_temperature - 50) * 100),1460.present_types = AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION |1461AP_Servo_Telem::TelemetryData::Types::VOLTAGE |1462AP_Servo_Telem::TelemetryData::Types::CURRENT |1463AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE |1464AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP1465};14661467servo_telem->update_telem_data(msg.actuator_id, telem_data);1468}1469#endif14701471/*1472handle ESC status message1473*/1474void AP_DroneCAN::handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg)1475{1476#if HAL_WITH_ESC_TELEM1477const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER);1478const uint8_t esc_index = msg.esc_index + esc_offset;14791480if (!is_esc_data_index_valid(esc_index)) {1481return;1482}14831484TelemetryData t {1485.temperature_cdeg = int16_t((KELVIN_TO_C(msg.temperature)) * 100),1486.voltage = msg.voltage,1487.current = msg.current,1488#if AP_EXTENDED_ESC_TELEM_ENABLED1489.power_percentage = msg.power_rating_pct,1490#endif1491};14921493update_rpm(esc_index, msg.rpm, msg.error_count);1494update_telem_data(esc_index, t,1495(isnan(msg.current) ? 0 : AP_ESC_Telem_Backend::TelemetryType::CURRENT)1496| (isnan(msg.voltage) ? 0 : AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)1497| (isnan(msg.temperature) ? 0 : AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE)1498#if AP_EXTENDED_ESC_TELEM_ENABLED1499| AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE1500#endif1501);1502#endif // HAL_WITH_ESC_TELEM1503}15041505#if AP_EXTENDED_ESC_TELEM_ENABLED1506/*1507handle Extended ESC status message1508*/1509void AP_DroneCAN::handle_esc_ext_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_StatusExtended& msg)1510{1511const uint8_t esc_offset = constrain_int16(_esc_offset.get(), 0, DRONECAN_SRV_NUMBER);1512const uint8_t esc_index = msg.esc_index + esc_offset;15131514if (!is_esc_data_index_valid(esc_index)) {1515return;1516}15171518TelemetryData telemetryData {1519.motor_temp_cdeg = (int16_t)(msg.motor_temperature_degC * 100),1520.input_duty = msg.input_pct,1521.output_duty = msg.output_pct,1522.flags = msg.status_flags,1523};15241525update_telem_data(esc_index, telemetryData,1526AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE1527| AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY1528| AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY1529| AP_ESC_Telem_Backend::TelemetryType::FLAGS);1530}1531#endif // AP_EXTENDED_ESC_TELEM_ENABLED15321533bool AP_DroneCAN::is_esc_data_index_valid(const uint8_t index) {1534if (index > DRONECAN_SRV_NUMBER) {1535// printf("DroneCAN: invalid esc index: %d. max index allowed: %d\n\r", index, DRONECAN_SRV_NUMBER);1536return false;1537}1538return true;1539}15401541#if AP_SCRIPTING_ENABLED1542/*1543handle FlexDebug message, holding a copy locally for a lua script to access1544*/1545void AP_DroneCAN::handle_FlexDebug(const CanardRxTransfer& transfer, const dronecan_protocol_FlexDebug &msg)1546{1547if (!option_is_set(Options::ENABLE_FLEX_DEBUG)) {1548return;1549}15501551// find an existing element in the list1552const uint8_t source_node = transfer.source_node_id;1553for (auto *p = flexDebug_list; p != nullptr; p = p->next) {1554if (p->node_id == source_node && p->msg.id == msg.id) {1555p->msg = msg;1556p->timestamp_us = uint32_t(transfer.timestamp_usec);1557return;1558}1559}15601561// new message ID, add to the list. Note that this gets called1562// only from one thread, so no lock needed1563auto *p = NEW_NOTHROW FlexDebug;1564if (p == nullptr) {1565return;1566}1567p->node_id = source_node;1568p->msg = msg;1569p->timestamp_us = uint32_t(transfer.timestamp_usec);1570p->next = flexDebug_list;15711572// link into the list1573flexDebug_list = p;1574}15751576/*1577get the last FlexDebug message from a node1578*/1579bool AP_DroneCAN::get_FlexDebug(uint8_t node_id, uint16_t msg_id, uint32_t ×tamp_us, dronecan_protocol_FlexDebug &msg) const1580{1581for (const auto *p = flexDebug_list; p != nullptr; p = p->next) {1582if (p->node_id == node_id && p->msg.id == msg_id) {1583if (timestamp_us == p->timestamp_us) {1584// stale message1585return false;1586}1587timestamp_us = p->timestamp_us;1588msg = p->msg;1589return true;1590}1591}1592return false;1593}15941595#endif // AP_SCRIPTING_ENABLED15961597/*1598handle LogMessage debug1599*/1600void AP_DroneCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg)1601{1602#if AP_HAVE_GCS_SEND_TEXT1603const auto log_level = AP::can().get_log_level();1604const auto msg_level = msg.level.value;1605bool send_mavlink = false;16061607if (log_level != AP_CANManager::LOG_NONE) {1608// log to onboard log and mavlink1609enum MAV_SEVERITY mavlink_level = MAV_SEVERITY_INFO;1610switch (msg_level) {1611case UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_DEBUG:1612mavlink_level = MAV_SEVERITY_DEBUG;1613send_mavlink = uint8_t(log_level) >= uint8_t(AP_CANManager::LogLevel::LOG_DEBUG);1614break;1615case UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_INFO:1616mavlink_level = MAV_SEVERITY_INFO;1617send_mavlink = uint8_t(log_level) >= uint8_t(AP_CANManager::LogLevel::LOG_INFO);1618break;1619case UAVCAN_PROTOCOL_DEBUG_LOGLEVEL_WARNING:1620mavlink_level = MAV_SEVERITY_WARNING;1621send_mavlink = uint8_t(log_level) >= uint8_t(AP_CANManager::LogLevel::LOG_WARNING);1622break;1623default:1624send_mavlink = uint8_t(log_level) >= uint8_t(AP_CANManager::LogLevel::LOG_ERROR);1625mavlink_level = MAV_SEVERITY_ERROR;1626break;1627}1628if (send_mavlink) {1629// when we send as MAVLink it also gets logged locally, so1630// we return to avoid a duplicate1631GCS_SEND_TEXT(mavlink_level, "CAN[%u] %s", transfer.source_node_id, msg.text.data);1632return;1633}1634}1635#endif // AP_HAVE_GCS_SEND_TEXT16361637#if HAL_LOGGING_ENABLED1638// always log locally if we have logging enabled1639AP::logger().Write_MessageF("CAN[%u] %s", transfer.source_node_id, msg.text.data);1640#endif1641}16421643/*1644check for parameter get/set response timeout1645*/1646void AP_DroneCAN::check_parameter_callback_timeout()1647{1648WITH_SEMAPHORE(_param_sem);16491650// return immediately if not waiting for get/set parameter response1651if (param_request_sent_ms == 0) {1652return;1653}16541655const uint32_t now_ms = AP_HAL::millis();1656if (now_ms - param_request_sent_ms > AP_DRONECAN_GETSET_TIMEOUT_MS) {1657param_request_sent_ms = 0;1658param_int_cb = nullptr;1659param_float_cb = nullptr;1660param_string_cb = nullptr;1661}1662}16631664/*1665send any queued request to get/set parameter1666called from loop1667*/1668void AP_DroneCAN::send_parameter_request()1669{1670WITH_SEMAPHORE(_param_sem);1671if (param_request_sent) {1672return;1673}1674param_get_set_client.request(param_request_node_id, param_getset_req);1675param_request_sent = true;1676}16771678/*1679set named float parameter on node1680*/1681bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb)1682{1683WITH_SEMAPHORE(_param_sem);16841685// fail if waiting for any previous get/set request1686if (param_int_cb != nullptr ||1687param_float_cb != nullptr ||1688param_string_cb != nullptr) {1689return false;1690}1691param_getset_req.index = 0;1692param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1);1693param_getset_req.value.real_value = value;1694param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;1695param_float_cb = cb;1696param_request_sent = false;1697param_request_sent_ms = AP_HAL::millis();1698param_request_node_id = node_id;1699return true;1700}17011702/*1703set named integer parameter on node1704*/1705bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb)1706{1707WITH_SEMAPHORE(_param_sem);17081709// fail if waiting for any previous get/set request1710if (param_int_cb != nullptr ||1711param_float_cb != nullptr ||1712param_string_cb != nullptr) {1713return false;1714}1715param_getset_req.index = 0;1716param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1);1717param_getset_req.value.integer_value = value;1718param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;1719param_int_cb = cb;1720param_request_sent = false;1721param_request_sent_ms = AP_HAL::millis();1722param_request_node_id = node_id;1723return true;1724}17251726/*1727set named string parameter on node1728*/1729bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, const string &value, ParamGetSetStringCb *cb)1730{1731WITH_SEMAPHORE(_param_sem);17321733// fail if waiting for any previous get/set request1734if (param_int_cb != nullptr ||1735param_float_cb != nullptr ||1736param_string_cb != nullptr) {1737return false;1738}1739param_getset_req.index = 0;1740param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1);1741memcpy(¶m_getset_req.value.string_value, (const void*)&value, sizeof(value));1742param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE;1743param_string_cb = cb;1744param_request_sent = false;1745param_request_sent_ms = AP_HAL::millis();1746param_request_node_id = node_id;1747return true;1748}17491750/*1751get named float parameter on node1752*/1753bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb)1754{1755WITH_SEMAPHORE(_param_sem);17561757// fail if waiting for any previous get/set request1758if (param_int_cb != nullptr ||1759param_float_cb != nullptr ||1760param_string_cb != nullptr) {1761return false;1762}1763param_getset_req.index = 0;1764param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data));1765param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY;1766param_float_cb = cb;1767param_request_sent = false;1768param_request_sent_ms = AP_HAL::millis();1769param_request_node_id = node_id;1770return true;1771}17721773/*1774get named integer parameter on node1775*/1776bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb)1777{1778WITH_SEMAPHORE(_param_sem);17791780// fail if waiting for any previous get/set request1781if (param_int_cb != nullptr ||1782param_float_cb != nullptr ||1783param_string_cb != nullptr) {1784return false;1785}1786param_getset_req.index = 0;1787param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data));1788param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY;1789param_int_cb = cb;1790param_request_sent = false;1791param_request_sent_ms = AP_HAL::millis();1792param_request_node_id = node_id;1793return true;1794}17951796/*1797get named string parameter on node1798*/1799bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetStringCb *cb)1800{1801WITH_SEMAPHORE(_param_sem);18021803// fail if waiting for any previous get/set request1804if (param_int_cb != nullptr ||1805param_float_cb != nullptr ||1806param_string_cb != nullptr) {1807return false;1808}1809param_getset_req.index = 0;1810param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data));1811param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY;1812param_string_cb = cb;1813param_request_sent = false;1814param_request_sent_ms = AP_HAL::millis();1815param_request_node_id = node_id;1816return true;1817}18181819void AP_DroneCAN::handle_param_get_set_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_GetSetResponse& rsp)1820{1821WITH_SEMAPHORE(_param_sem);1822if (!param_int_cb &&1823!param_float_cb &&1824!param_string_cb) {1825return;1826}1827if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) && param_int_cb) {1828int32_t val = rsp.value.integer_value;1829if ((*param_int_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) {1830// we want the parameter to be set with val1831param_getset_req.index = 0;1832memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len);1833param_getset_req.value.integer_value = val;1834param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;1835param_request_sent = false;1836param_request_sent_ms = AP_HAL::millis();1837param_request_node_id = transfer.source_node_id;1838return;1839}1840} else if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) && param_float_cb) {1841float val = rsp.value.real_value;1842if ((*param_float_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) {1843// we want the parameter to be set with val1844param_getset_req.index = 0;1845memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len);1846param_getset_req.value.real_value = val;1847param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;1848param_request_sent = false;1849param_request_sent_ms = AP_HAL::millis();1850param_request_node_id = transfer.source_node_id;1851return;1852}1853} else if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) && param_string_cb) {1854string val;1855memcpy(&val, &rsp.value.string_value, sizeof(val));1856if ((*param_string_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) {1857// we want the parameter to be set with val1858param_getset_req.index = 0;1859memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len);1860memcpy(¶m_getset_req.value.string_value, &val, sizeof(val));1861param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE;1862param_request_sent = false;1863param_request_sent_ms = AP_HAL::millis();1864param_request_node_id = transfer.source_node_id;1865return;1866}1867}18681869param_request_sent_ms = 0;1870param_int_cb = nullptr;1871param_float_cb = nullptr;1872param_string_cb = nullptr;1873}18741875void AP_DroneCAN::send_parameter_save_request()1876{1877WITH_SEMAPHORE(_param_save_sem);1878if (param_save_request_sent) {1879return;1880}1881param_save_client.request(param_save_request_node_id, param_save_req);1882param_save_request_sent = true;1883}18841885bool AP_DroneCAN::save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb)1886{1887WITH_SEMAPHORE(_param_save_sem);1888if (save_param_cb != nullptr) {1889//busy1890return false;1891}18921893param_save_req.opcode = UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_REQUEST_OPCODE_SAVE;1894param_save_request_sent = false;1895param_save_request_node_id = node_id;1896save_param_cb = cb;1897return true;1898}18991900// handle parameter save request response1901void AP_DroneCAN::handle_param_save_response(const CanardRxTransfer& transfer, const uavcan_protocol_param_ExecuteOpcodeResponse& rsp)1902{1903WITH_SEMAPHORE(_param_save_sem);1904if (!save_param_cb) {1905return;1906}1907(*save_param_cb)(this, transfer.source_node_id, rsp.ok);1908save_param_cb = nullptr;1909}19101911// Send Reboot command1912// Note: Do not call this from outside DroneCAN thread context,1913// THIS IS NOT A THREAD SAFE API!1914void AP_DroneCAN::send_reboot_request(uint8_t node_id)1915{1916uavcan_protocol_RestartNodeRequest request;1917request.magic_number = UAVCAN_PROTOCOL_RESTARTNODE_REQUEST_MAGIC_NUMBER;1918restart_node_client.request(node_id, request);1919}19201921// check if a option is set and if it is then reset it to 0.1922// return true if it was set1923bool AP_DroneCAN::check_and_reset_option(Options option)1924{1925bool ret = option_is_set(option);1926if (ret) {1927_options.set_and_save(int16_t(_options.get() & ~uint16_t(option)));1928}1929return ret;1930}19311932// handle prearm check1933bool AP_DroneCAN::prearm_check(char* fail_msg, uint8_t fail_msg_len) const1934{1935// forward this to DNA_Server1936return _dna_server.prearm_check(fail_msg, fail_msg_len);1937}19381939/*1940periodic logging1941*/1942void AP_DroneCAN::logging(void)1943{1944#if HAL_LOGGING_ENABLED1945const uint32_t now_ms = AP_HAL::millis();1946if (now_ms - last_log_ms < 1000) {1947return;1948}1949last_log_ms = now_ms;1950if (HAL_NUM_CAN_IFACES <= _driver_index) {1951// no interface?1952return;1953}1954const auto *iface = hal.can[_driver_index];1955if (iface == nullptr) {1956return;1957}1958const auto *stats = iface->get_statistics();1959if (stats == nullptr) {1960// statistics not implemented on this interface1961return;1962}1963const auto &s = *stats;19641965// @LoggerMessage: CANS1966// @Description: CAN Bus Statistics1967// @Field: TimeUS: Time since system startup1968// @Field: I: driver index1969// @Field: T: transmit success count1970// @Field: Trq: transmit request count1971// @Field: Trej: transmit reject count1972// @Field: Tov: transmit overflow count1973// @Field: Tto: transmit timeout count1974// @Field: Tab: transmit abort count1975// @Field: R: receive count1976// @Field: Rov: receive overflow count1977// @Field: Rer: receive error count1978// @Field: Bo: bus offset error count1979// @Field: Etx: ESC successful send count1980// @Field: Stx: Servo successful send count1981// @Field: Ftx: ESC/Servo failed-to-send count1982AP::logger().WriteStreaming("CANS",1983"TimeUS,I,T,Trq,Trej,Tov,Tto,Tab,R,Rov,Rer,Bo,Etx,Stx,Ftx",1984"s#-------------",1985"F--------------",1986"QBIIIIIIIIIIIII",1987AP_HAL::micros64(),1988_driver_index,1989s.tx_success,1990s.tx_requests,1991s.tx_rejected,1992s.tx_overflow,1993s.tx_timedout,1994s.tx_abort,1995s.rx_received,1996s.rx_overflow,1997s.rx_errors,1998s.num_busoff_err,1999_esc_send_count,2000_srv_send_count,2001_fail_send_count);2002#endif // HAL_LOGGING_ENABLED2003}20042005// add an 11 bit auxillary driver2006bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor)2007{2008return canard_iface.add_11bit_driver(sensor);2009}20102011// handler for outgoing frames for auxillary drivers2012bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)2013{2014if (out_frame.isExtended() && !option_is_set(Options::ALLOW_EXTENDED_AUX)) {2015// don't allow extended frames to be sent by auxillary driver unless2016// the user has specifically allowed it2017return false;2018}2019return canard_iface.write_aux_frame(out_frame, timeout_us);2020}20212022#endif // HAL_NUM_CAN_IFACES202320242025