Path: blob/master/libraries/AP_CANManager/AP_MAVLinkCAN.cpp
4182 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 HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED2021extern const AP_HAL::HAL& hal;2223/*24handle MAV_CMD_CAN_FORWARD mavlink long command25*/26bool AP_MAVLinkCAN::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg)27{28WITH_SEMAPHORE(can_forward.sem);29const int8_t bus = int8_t(packet.param1)-1;3031if (bus == -1) {32/*33a request to stop forwarding34*/35if (can_forward.callback_id != 0) {36hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);37can_forward.callback_id = 0;38}39return true;40}4142if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {43return false;44}4546if (can_forward.callback_id != 0 && can_forward.callback_bus != bus) {47/*48the client is changing which bus they are monitoring, unregister from the previous bus49*/50hal.can[can_forward.callback_bus]->unregister_frame_callback(can_forward.callback_id);51can_forward.callback_id = 0;52}5354if (can_forward.callback_id == 0 &&55!hal.can[bus]->register_frame_callback(56FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags), can_forward.callback_id)) {57// failed to register the callback58return false;59}6061can_forward.callback_bus = bus;62can_forward.last_callback_enable_ms = AP_HAL::millis();63can_forward.chan = chan;64can_forward.system_id = msg.sysid;65can_forward.component_id = msg.compid;6667return true;68}6970/*71handle a CAN_FRAME packet72*/73void AP_MAVLinkCAN::handle_can_frame(const mavlink_message_t &msg)74{75if (frame_buffer == nullptr) {76// allocate frame buffer77// 20 is good for firmware upload78uint8_t buffer_size = 20;79WITH_SEMAPHORE(frame_buffer_sem);80while (frame_buffer == nullptr && buffer_size > 0) {81// we'd like 20 frames, but will live with less82frame_buffer = NEW_NOTHROW ObjectBuffer<BufferFrame>(buffer_size);83if (frame_buffer != nullptr && frame_buffer->get_size() != 0) {84// register a callback for when frames can't be sent immediately85hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_MAVLinkCAN::process_frame_buffer, void));86break;87}88delete frame_buffer;89frame_buffer = nullptr;90buffer_size /= 2;91}92if (frame_buffer == nullptr) {93// discard the frames94return;95}96}9798switch (msg.msgid) {99case MAVLINK_MSG_ID_CAN_FRAME: {100mavlink_can_frame_t p;101mavlink_msg_can_frame_decode(&msg, &p);102if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {103return;104}105struct BufferFrame frame {106bus : p.bus,107frame : AP_HAL::CANFrame(p.id, p.data, p.len)108};109{110WITH_SEMAPHORE(frame_buffer_sem);111frame_buffer->push(frame);112}113break;114}115#if HAL_CANFD_SUPPORTED116case MAVLINK_MSG_ID_CANFD_FRAME: {117mavlink_canfd_frame_t p;118mavlink_msg_canfd_frame_decode(&msg, &p);119if (p.bus >= HAL_NUM_CAN_IFACES || hal.can[p.bus] == nullptr) {120return;121}122struct BufferFrame frame {123bus : p.bus,124frame : AP_HAL::CANFrame(p.id, p.data, p.len, true)125};126{127WITH_SEMAPHORE(frame_buffer_sem);128frame_buffer->push(frame);129}130break;131}132#endif133}134process_frame_buffer();135}136137/*138process the frame buffer139*/140void AP_MAVLinkCAN::process_frame_buffer()141{142while (frame_buffer) {143WITH_SEMAPHORE(frame_buffer_sem);144struct BufferFrame frame;145const uint16_t timeout_us = 2000;146if (!frame_buffer->peek(frame)) {147// no frames in the queue148break;149}150const int16_t retcode = hal.can[frame.bus]->send(frame.frame,151AP_HAL::micros64() + timeout_us,152AP_HAL::CANIface::IsForwardedFrame);153if (retcode == 0) {154// no space in the CAN output slots, try again later155break;156}157// retcode == 1 means sent, -1 means a frame that can't be158// sent. Either way we should remove from the queue159frame_buffer->pop();160}161}162163/*164handle a CAN_FILTER_MODIFY packet165*/166void AP_MAVLinkCAN::handle_can_filter_modify(const mavlink_message_t &msg)167{168mavlink_can_filter_modify_t p;169mavlink_msg_can_filter_modify_decode(&msg, &p);170const int8_t bus = int8_t(p.bus)-1;171if (bus >= HAL_NUM_CAN_IFACES || hal.can[bus] == nullptr) {172return;173}174if (p.num_ids > ARRAY_SIZE(p.ids)) {175return;176}177uint16_t *new_ids = nullptr;178uint16_t num_new_ids = 0;179WITH_SEMAPHORE(can_forward.sem);180181// sort the list, so we can bisection search and the array182// operations below are efficient183insertion_sort_uint16(p.ids, p.num_ids);184185switch (p.operation) {186case CAN_FILTER_REPLACE: {187if (p.num_ids == 0) {188can_forward.num_filter_ids = 0;189delete[] can_forward.filter_ids;190can_forward.filter_ids = nullptr;191return;192}193if (p.num_ids == can_forward.num_filter_ids &&194memcmp(p.ids, can_forward.filter_ids, p.num_ids*sizeof(uint16_t)) == 0) {195// common case of replacing with identical list196return;197}198new_ids = NEW_NOTHROW uint16_t[p.num_ids];199if (new_ids != nullptr) {200num_new_ids = p.num_ids;201memcpy((void*)new_ids, (const void *)p.ids, p.num_ids*sizeof(uint16_t));202}203break;204}205case CAN_FILTER_ADD: {206if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,207p.ids, p.num_ids) == p.num_ids) {208// nothing changing209return;210}211new_ids = NEW_NOTHROW uint16_t[can_forward.num_filter_ids+p.num_ids];212if (new_ids == nullptr) {213return;214}215if (can_forward.num_filter_ids != 0) {216memcpy(new_ids, can_forward.filter_ids, can_forward.num_filter_ids*sizeof(uint16_t));217}218memcpy(&new_ids[can_forward.num_filter_ids], p.ids, p.num_ids*sizeof(uint16_t));219insertion_sort_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);220num_new_ids = remove_duplicates_uint16(new_ids, can_forward.num_filter_ids+p.num_ids);221break;222}223case CAN_FILTER_REMOVE: {224if (common_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,225p.ids, p.num_ids) == 0) {226// nothing changing227return;228}229can_forward.num_filter_ids = remove_list_uint16(can_forward.filter_ids, can_forward.num_filter_ids,230p.ids, p.num_ids);231if (can_forward.num_filter_ids == 0) {232delete[] can_forward.filter_ids;233can_forward.filter_ids = nullptr;234}235break;236}237}238if (new_ids != nullptr) {239// handle common case of no change240if (num_new_ids == can_forward.num_filter_ids &&241memcmp(new_ids, can_forward.filter_ids, num_new_ids*sizeof(uint16_t)) == 0) {242delete[] new_ids;243} else {244// put the new list in place245delete[] can_forward.filter_ids;246can_forward.filter_ids = new_ids;247can_forward.num_filter_ids = num_new_ids;248}249}250}251252/*253handler for CAN frames from the registered callback, sending frames254out as CAN_FRAME or CANFD_FRAME messages255*/256void AP_MAVLinkCAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)257{258mavlink_channel_t chan;259uint8_t system_id;260uint8_t component_id;261{262WITH_SEMAPHORE(can_forward.sem);263if (bus != can_forward.callback_bus) {264// we are not registered for forwarding this bus, discard frame265return;266}267if (can_forward.frame_counter++ == 100) {268// check every 100 frames for disabling CAN_FRAME send269// we stop sending after 5s if the client stops270// sending MAV_CMD_CAN_FORWARD requests271if (can_forward.callback_id != 0 &&272AP_HAL::millis() - can_forward.last_callback_enable_ms > 5000) {273hal.can[bus]->unregister_frame_callback(can_forward.callback_id);274can_forward.callback_id = 0;275return;276}277can_forward.frame_counter = 0;278}279if (can_forward.filter_ids != nullptr) {280// work out ID of this frame281uint16_t id = 0;282if ((frame.id&0xff) != 0) {283// not anonymous284if (frame.id & 0x80) {285// service message286id = uint8_t(frame.id>>16);287} else {288// message frame289id = uint16_t(frame.id>>8);290}291}292if (!bisect_search_uint16(can_forward.filter_ids, can_forward.num_filter_ids, id)) {293return;294}295}296// remeber destination while we hold the mutex297chan = can_forward.chan;298system_id = can_forward.system_id;299component_id = can_forward.component_id;300}301302// the rest is run without the can_forward.sem303WITH_SEMAPHORE(comm_chan_lock(chan));304const uint8_t data_len = AP_HAL::CANFrame::dlcToDataLength(frame.dlc);305#if HAL_CANFD_SUPPORTED306if (frame.isCanFDFrame()) {307if (HAVE_PAYLOAD_SPACE(chan, CANFD_FRAME)) {308mavlink_msg_canfd_frame_send(chan, system_id, component_id,309bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));310}311} else312#endif313{314if (HAVE_PAYLOAD_SPACE(chan, CAN_FRAME)) {315mavlink_msg_can_frame_send(chan, system_id, component_id,316bus, data_len, frame.id, const_cast<uint8_t*>(frame.data));317}318}319}320321#endif // HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED322323324