Path: blob/master/libraries/AP_CANManager/AP_MAVLinkCAN.cpp
9478 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*/1415#include "AP_MAVLinkCAN.h"16#include <AP_HAL/utility/sparse-endian.h>17#include <AP_Common/sorting.h>1819#if AP_MAVLINKCAN_ENABLED2021extern const AP_HAL::HAL& hal;2223static AP_MAVLinkCAN *singleton;2425AP_MAVLinkCAN *AP_MAVLinkCAN::ensure_singleton()26{27if (singleton == nullptr) {28singleton = NEW_NOTHROW AP_MAVLinkCAN();29}30return singleton;31}3233bool AP_MAVLinkCAN::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)34{35auto *s = ensure_singleton();36if (s == nullptr) {37return false;38}39return singleton->_handle_can_forward(chan, packet, msg);40}4142void AP_MAVLinkCAN::handle_can_frame(const mavlink_message_t &msg)43{44auto *s = ensure_singleton();45if (s == nullptr) {46return;47}48singleton->_handle_can_frame(msg);49}5051void AP_MAVLinkCAN::handle_can_filter_modify(const mavlink_message_t &msg)52{53auto *s = ensure_singleton();54if (s == nullptr) {55return;56}57singleton->_handle_can_filter_modify(msg);58}596061/*62handle MAV_CMD_CAN_FORWARD mavlink long command63*/64bool AP_MAVLinkCAN::_handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)65{66WITH_SEMAPHORE(can_forward.sem);67const int8_t bus = int8_t(packet.param1)-1;6869if (bus == -1) {70/*71a request to stop forwarding72*/73if (can_forward.callback_id != 0) {74hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);75can_forward.callback_id = 0;76}77return true;78}7980if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {81return false;82}8384if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) {85/*86the client is changing which bus they are monitoring, unregister from the previous bus87*/88hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);89can_forward.callback_id = 0;90}9192if (can_forward.callback_id == 0 &&93!hal.can[bus]->register_frame_callback(94FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), can_forward.callback_id)) {95// failed to register the callback96return false;97}9899can_forward.callback_bus = bus;100can_forward.last_callback_enable_ms = AP_HAL::millis();101can_forward.chan = chan;102can_forward.system_id = msg.sysid;103can_forward.component_id = msg.compid;104105return true;106}107108/*109handle a CAN_FRAME packet110*/111void AP_MAVLinkCAN::_handle_can_frame(const mavlink_message_t &msg)112{113if (frame_buffer == nullptr) {114// allocate frame buffer115// 20 is good for firmware upload116uint8_t buffer_size = 20;117WITH_SEMAPHORE(frame_buffer_sem);118while (frame_buffer == nullptr && buffer_size > 0) {119// we'd like 20 frames, but will live with less120frame_buffer = NEW_NOTHROW ObjectBuffer<BufferFrame>(buffer_size);121if (frame_buffer != nullptr && frame_buffer->get_size() != 0) {122// register a callback for when frames can't be sent immediately123hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::process_frame_buffer, void));124break;125}126delete frame_buffer;127frame_buffer = nullptr;128buffer_size /= 2;129}130if (frame_buffer == nullptr) {131// discard the frames132return;133}134}135136switch (msg.msgid) {137case MAVLINK_MSG_ID_CAN_FRAME: {138mavlink_can_frame_t p;139mavlink_msg_can_frame_decode(&msg, &p);140if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {141return;142}143struct BufferFrame frame {144bus : p.bus,145frame : AP_HAL::CANFrame(p.id, p.data, p.len)146};147{148WITH_SEMAPHORE(frame_buffer_sem);149frame_buffer->push(frame);150}151break;152}153#if HAL_CANFD_SUPPORTED154case MAVLINK_MSG_ID_CANFD_FRAME: {155mavlink_canfd_frame_t p;156mavlink_msg_canfd_frame_decode(&msg, &p);157if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {158return;159}160struct BufferFrame frame {161bus : p.bus,162frame : AP_HAL::CANFrame(p.id, p.data, p.len, true)163};164{165WITH_SEMAPHORE(frame_buffer_sem);166frame_buffer->push(frame);167}168break;169}170#endif171}172process_frame_buffer();173}174175/*176process the frame buffer177*/178void AP_MAVLinkCAN::process_frame_buffer()179{180while (frame_buffer) {181WITH_SEMAPHORE(frame_buffer_sem);182struct BufferFrame frame;183const uint16_t timeout_us = 2000;184if (!frame_buffer->peek(frame)) {185// no frames in the queue186break;187}188const int16_t retcode = hal.can[frame.bus]->send(frame.frame,189AP_HAL::micros64() + timeout_us,190AP_HAL::CANIface::IsForwardedFrame);191if (retcode == 0) {192// no space in the CAN output slots, try again later193break;194}195// retcode == 1 means sent, -1 means a frame that can't be196// sent. Either way we should remove from the queue197frame_buffer->pop();198}199}200201/*202handle a CAN_FILTER_MODIFY packet203*/204void AP_MAVLinkCAN::_handle_can_filter_modify(const mavlink_message_t &msg)205{206mavlink_can_filter_modify_t p;207mavlink_msg_can_filter_modify_decode(&msg, &p);208const int8_t bus = int8_t(p.bus)-1;209if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {210return;211}212if (p.num_ids > ARRAY_SIZE(p.ids)) {213return;214}215uint16_t *new_ids = nullptr;216uint16_t num_new_ids = 0;217WITH_SEMAPHORE(can_forward.sem);218219// sort the list, so we can bisection search and the array220// operations below are efficient221insertion_sort_uint16(p.ids, p.num_ids);222223switch (p.operation) {224case CAN_FILTER_REPLACE: {225if (p.num_ids == 0) {226can_forward.num_filter_ids = 0;227delete[] can_forward.filter_ids;228can_forward.filter_ids = nullptr;229return;230}231if (p.num_ids == can_forward.num_filter_ids &&232memcmp(p.ids, can_forward.filter_ids, p.num_ids*sizeof(uint16_t)) == 0) {233// common case of replacing with identical list234return;235}236new_ids = NEW_NOTHROW uint16_t[p.num_ids];237if (new_ids != nullptr) {238num_new_ids = p.num_ids;239memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t));240}241break;242}243case CAN_FILTER_ADD: {244if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,245p.ids, p.num_ids) == p.num_ids) {246// nothing changing247return;248}249new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids];250if (new_ids == nullptr) {251return;252}253if (can_forward.num_filter_ids != 0) {254memcpy(new_ids, can_forward.filter_ids, can_forward.num_filter_ids*sizeof(uint16_t));255}256memcpy(&new_ids[can_forward.num_filter_ids], p.ids, p.num_ids*sizeof(uint16_t));257insertion_sort_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);258num_new_ids = remove_duplicates_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);259break;260}261case CAN_FILTER_REMOVE: {262if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,263p.ids, p.num_ids) == 0) {264// nothing changing265return;266}267can_forward.num_filter_ids = remove_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,268p.ids, p.num_ids);269if (can_forward.num_filter_ids == 0) {270delete[] can_forward.filter_ids;271can_forward.filter_ids = nullptr;272}273break;274}275}276if (new_ids != nullptr) {277// handle common case of no change278if (num_new_ids == can_forward.num_filter_ids &&279memcmp(new_ids, can_forward.filter_ids, num_new_ids*sizeof(uint16_t)) == 0) {280delete[] new_ids;281} else {282// put the new list in place283delete[] can_forward.filter_ids;284can_forward.filter_ids = new_ids;285can_forward.num_filter_ids = num_new_ids;286}287}288}289290/*291handler for CAN frames from the registered callback, sending frames292out as CAN_FRAME or CANFD_FRAME messages293*/294void AP_MAVLinkCAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)295{296mavlink_channel_t chan;297uint8_t system_id;298uint8_t component_id;299{300WITH_SEMAPHORE(can_forward.sem);301if (bus != can_forward.callback_bus) {302// we are not registered for forwarding this bus, discard frame303return;304}305if (can_forward.frame_counter++ == 100) {306// check every 100 frames for disabling CAN_FRAME send307// we stop sending after 5s if the client stops308// sending MAV_CMD_CAN_FORWARD requests309if (can_forward.callback_id != 0 &&310AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) {311hal.can[bus]->unregister_frame_callback(can_forward.callback_id);312can_forward.callback_id = 0;313return;314}315can_forward.frame_counter = 0;316}317if (can_forward.filter_ids != nullptr) {318// work out ID of this frame319uint16_t id = 0;320if ((frame.id&0xff) != 0) {321// not anonymous322if (frame.id & 0x80) {323// service message324id = uint8_t(frame.id>>16);325} else {326// message frame327id = uint16_t(frame.id>>8);328}329}330if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) {331return;332}333}334// remeber destination while we hold the mutex335chan = can_forward.chan;336system_id = can_forward.system_id;337component_id = can_forward.component_id;338}339340// the rest is run without the can_forward.sem341WITH_SEMAPHORE(comm_chan_lock(chan));342const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc);343#if HAL_CANFD_SUPPORTED344if (frame.isCanFDFrame()) {345if (HAVE_PAYLOAD_SPACE(chan, CANFD_FRAME)) {346mavlink_msg_canfd_frame_send(chan, system_id, component_id,347bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));348}349} else350#endif351{352if (HAVE_PAYLOAD_SPACE(chan, CAN_FRAME)) {353mavlink_msg_can_frame_send(chan, system_id, component_id,354bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));355}356}357}358359#endif // AP_MAVLINKCAN_ENABLED360361362