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/libraries/AP_CANManager/AP_CANManager.h
Views: 1798
/*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* Code by Siddharth Bharat Purohit15*/1617#pragma once1819#include "AP_CANManager_config.h"2021#if HAL_CANMANAGER_ENABLED2223#include <AP_HAL/AP_HAL.h>2425#include <AP_Param/AP_Param.h>26#include "AP_SLCANIface.h"27#include "AP_CANDriver.h"28#include <GCS_MAVLink/GCS_config.h>29#if HAL_GCS_ENABLED30#include <GCS_MAVLink/GCS_MAVLink.h>31#include <AP_HAL/utility/RingBuffer.h>32#endif3334#include "AP_CAN.h"3536class CANSensor;3738class AP_CANManager39{40public:41AP_CANManager();4243/* Do not allow copies */44CLASS_NO_COPY(AP_CANManager);4546static AP_CANManager* get_singleton()47{48if (_singleton == nullptr) {49AP_HAL::panic("CANManager used before allocation.");50}51return _singleton;52}5354enum LogLevel : uint8_t {55LOG_NONE,56LOG_ERROR,57LOG_WARNING,58LOG_INFO,59LOG_DEBUG,60};6162void init(void);6364// register a new driver65bool register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver);6667// register a new auxillary sensor driver for 11 bit address frames68bool register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index);6970// returns number of active CAN Drivers71uint8_t get_num_drivers(void) const72{73return HAL_MAX_CAN_PROTOCOL_DRIVERS;74}7576// return driver for index i77AP_CANDriver* get_driver(uint8_t i) const78{79if (i < ARRAY_SIZE(_drivers)) {80return _drivers[i];81}82return nullptr;83}8485// returns current log level86LogLevel get_log_level(void) const87{88return LogLevel(_loglevel.get());89}9091// Method to log status and debug information for review while debugging92void log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...) FMT_PRINTF(4,5);9394void log_retrieve(ExpandingString &str) const;9596// return driver type index i97AP_CAN::Protocol get_driver_type(uint8_t i) const98{99if (i < ARRAY_SIZE(_driver_type_cache)) {100return _driver_type_cache[i];101}102return AP_CAN::Protocol::None;103}104105static const struct AP_Param::GroupInfo var_info[];106107#if HAL_GCS_ENABLED108bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg);109void handle_can_frame(const mavlink_message_t &msg);110void handle_can_filter_modify(const mavlink_message_t &msg);111#endif112113private:114115// Parameter interface for CANIfaces116class CANIface_Params117{118friend class AP_CANManager;119120public:121CANIface_Params()122{123AP_Param::setup_object_defaults(this, var_info);124}125126static const struct AP_Param::GroupInfo var_info[];127128enum class Options : uint32_t {129LOG_ALL_FRAMES = (1U<<0),130};131132bool option_is_set(Options option) const {133return (_options & uint32_t(option)) != 0;134}135136private:137AP_Int8 _driver_number;138AP_Int32 _bitrate;139AP_Int32 _fdbitrate;140AP_Int32 _options;141142#if AP_CAN_LOGGING_ENABLED && HAL_LOGGING_ENABLED143uint8_t logging_id;144#endif145};146147//Parameter Interface for CANDrivers148class CANDriver_Params149{150friend class AP_CANManager;151152public:153CANDriver_Params()154{155AP_Param::setup_object_defaults(this, var_info);156}157static const struct AP_Param::GroupInfo var_info[];158159private:160AP_Int8 _driver_type;161AP_Int8 _driver_type_11bit;162AP_CANDriver* _uavcan;163AP_CANDriver* _piccolocan;164};165166CANIface_Params _interfaces[HAL_NUM_CAN_IFACES];167AP_CANDriver* _drivers[HAL_MAX_CAN_PROTOCOL_DRIVERS];168CANDriver_Params _drv_param[HAL_MAX_CAN_PROTOCOL_DRIVERS];169AP_CAN::Protocol _driver_type_cache[HAL_MAX_CAN_PROTOCOL_DRIVERS];170171AP_Int8 _loglevel;172uint8_t _num_drivers;173#if AP_CAN_SLCAN_ENABLED174SLCAN::CANIface _slcan_interface;175#endif176177static AP_CANManager *_singleton;178179char* _log_buf;180uint32_t _log_pos;181182HAL_Semaphore _sem;183184#if HAL_GCS_ENABLED185/*186handler for CAN frames from the registered callback, sending frames187out as CAN_FRAME messages188*/189void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame);190191struct {192mavlink_channel_t chan;193uint8_t system_id;194uint8_t component_id;195uint8_t frame_counter;196uint32_t last_callback_enable_ms;197HAL_Semaphore sem;198uint16_t num_filter_ids;199uint16_t *filter_ids;200uint8_t callback_id;201uint8_t callback_bus;202} can_forward;203204// buffer for MAVCAN frames205struct BufferFrame {206uint8_t bus;207AP_HAL::CANFrame frame;208};209ObjectBuffer<BufferFrame> *frame_buffer;210211void process_frame_buffer(void);212#endif // HAL_GCS_ENABLED213214#if AP_CAN_LOGGING_ENABLED && HAL_LOGGING_ENABLED215/*216handler for CAN frames for logging217*/218void can_logging_callback(uint8_t bus, const AP_HAL::CANFrame &frame);219void check_logging_enable(void);220#endif221};222223namespace AP224{225AP_CANManager& can();226}227228#endif // HAL_CANMANAGER_ENABLED229230231