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_SLCANIface.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 AP_CAN_SLCAN_ENABLED2223#include <AP_HAL/AP_HAL.h>24#include "AP_HAL/utility/RingBuffer.h"25#include <AP_Param/AP_Param.h>2627#define SLCAN_BUFFER_SIZE 20028#define SLCAN_RX_QUEUE_SIZE 642930#ifndef HAL_CAN_RX_QUEUE_SIZE31#define HAL_CAN_RX_QUEUE_SIZE 12832#endif3334static_assert(HAL_CAN_RX_QUEUE_SIZE <= 254, "Invalid CAN Rx queue size");3536namespace SLCAN37{3839class CANIface: public AP_HAL::CANIface40{4142int16_t reportFrame(const AP_HAL::CANFrame& frame, uint64_t timestamp_usec);4344const char* processCommand(char* cmd);4546// pushes received frame into queue, false if failed47bool push_Frame(AP_HAL::CANFrame &frame);4849// Methods to handle different types of frames,50// return true if successfully received frame type51bool handle_FrameRTRStd(const char* cmd);52bool handle_FrameRTRExt(const char* cmd);53bool handle_FrameDataStd(const char* cmd);54bool handle_FrameDataExt(const char* cmd, bool canfd);5556bool handle_FDFrameDataExt(const char* cmd);5758// Parsing bytes received on the serial port59inline void addByte(const uint8_t byte);6061// track changes to slcan serial port62void update_slcan_port();6364bool initialized_;6566char buf_[SLCAN_BUFFER_SIZE + 1]; // buffer to record raw frame nibbles before parsing67int16_t pos_ = 0; // position in the buffer recording nibble frames before parsing68AP_HAL::UARTDriver* _port; // UART interface port reference to be used for SLCAN iface6970ObjectBuffer<AP_HAL::CANIface::CanRxItem> rx_queue_; // Parsed Rx Frame queue7172const uint32_t _serial_lock_key = 0x53494442; // Key used to lock UART port for use by slcan7374AP_Int8 _slcan_can_port;75AP_Int8 _slcan_ser_port;76AP_Int8 _slcan_timeout;77AP_Int8 _slcan_start_delay;7879bool _slcan_start_req;80uint32_t _slcan_start_req_time;81int8_t _prev_ser_port;82int8_t _iface_num = -1;83uint32_t _last_had_activity;84uint8_t num_tries;85AP_HAL::CANIface* _can_iface; // Can interface to be used for interaction by SLCAN interface86HAL_Semaphore port_sem;87bool _set_by_sermgr;88public:89CANIface():90rx_queue_(HAL_CAN_RX_QUEUE_SIZE)91{92AP_Param::setup_object_defaults(this, var_info);93}9495static const struct AP_Param::GroupInfo var_info[];9697bool init(const uint32_t bitrate, const OperatingMode mode) override98{99return false;100}101102// Initialisation of SLCAN Passthrough method of operation103bool init_passthrough(uint8_t i);104105void set_can_iface(AP_HAL::CANIface* can_iface)106{107_can_iface = can_iface;108}109110void reset_params();111112// Overriden methods113bool set_event_handle(AP_HAL::BinarySemaphore *sem_handle) override;114uint16_t getNumFilters() const override;115uint32_t getErrorCount() const override;116void get_stats(ExpandingString &) override;117bool is_busoff() const override;118bool configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs) override;119void flush_tx() override;120void clear_rx() override;121bool is_initialized() const override;122bool select(bool &read, bool &write,123const AP_HAL::CANFrame* const pending_tx,124uint64_t blocking_deadline) override;125int16_t send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline,126AP_HAL::CANIface::CanIOFlags flags) override;127128int16_t receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,129AP_HAL::CANIface::CanIOFlags& out_flags) override;130131protected:132int8_t get_iface_num() const override {133return _iface_num;134}135136bool add_to_rx_queue(const AP_HAL::CANIface::CanRxItem &frm) override {137return rx_queue_.push(frm);138}139};140141}142143#endif // AP_CAN_SLCAN_ENABLED144145146