Path: blob/master/libraries/AP_CANManager/AP_MAVLinkCAN.h
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#pragma once1617#include <AP_HAL/AP_HAL.h>18#include <AP_HAL/utility/RingBuffer.h>19#include "AP_CANManager_config.h"2021#if HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED2223#include <GCS_MAVLink/GCS_MAVLink.h>24#include <AP_HAL/CANIface.h>25#include <AP_HAL/utility/OwnPtr.h>26#include <GCS_MAVLink/GCS.h>2728class AP_MAVLinkCAN {29public:30AP_MAVLinkCAN() {}3132// Process CAN frame forwarding33void process_frame_buffer();3435// Handle commands to forward CAN frames to GCS36bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg);3738// Handle received MAVLink CAN frames39void handle_can_frame(const mavlink_message_t &msg);4041// Handle CAN filter modification42void handle_can_filter_modify(const mavlink_message_t &msg);4344private:45// Callback for receiving CAN frames from CAN bus and sending to GCS46void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags);4748/*49* Structure to maintain forwarding state50*/51struct {52mavlink_channel_t chan;53uint8_t system_id;54uint8_t component_id;55uint8_t frame_counter;56uint32_t last_callback_enable_ms;57HAL_Semaphore sem;58uint16_t num_filter_ids;59uint16_t *filter_ids;60uint8_t callback_id;61uint8_t callback_bus;62} can_forward;6364// Buffer for storing CAN frames to be sent65struct BufferFrame {66uint8_t bus;67AP_HAL::CANFrame frame;68};6970// Frame buffer for queuing frames71HAL_Semaphore frame_buffer_sem;72ObjectBuffer<BufferFrame> *frame_buffer;73};7475#endif // HAL_CANMANAGER_ENABLED && HAL_GCS_ENABLED767778