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.cpp
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* Author: Siddharth Bharat Purohit15* Referenced from implementation by Pavel Kirienko <[email protected]>16* for Zubax Babel17*/1819#include "AP_SLCANIface.h"2021#if AP_CAN_SLCAN_ENABLED22#include <AP_HAL/AP_HAL.h>23#include <AP_Common/AP_Common.h>2425#include "AP_CANManager.h"2627#include <AP_SerialManager/AP_SerialManager.h>28#include <stdio.h>29#include <AP_Vehicle/AP_Vehicle_Type.h>30#include <GCS_MAVLink/GCS.h>3132#define LOG_TAG "SLCAN"3334extern const AP_HAL::HAL& hal;3536const AP_Param::GroupInfo SLCAN::CANIface::var_info[] = {37// @Param: CPORT38// @DisplayName: SLCAN Route39// @Description: CAN Interface ID to be routed to SLCAN, 0 means no routing40// @Values: 0:Disabled,1:First interface,2:Second interface41// @User: Standard42// @RebootRequired: True43AP_GROUPINFO("CPORT", 1, SLCAN::CANIface, _slcan_can_port, 0),4445// @Param: SERNUM46// @DisplayName: SLCAN Serial Port47// @Description: Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial. This parameter is automatically reset on reboot or on timeout. See CAN_SLCAN_TIMOUT for timeout details48// @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial649// @User: Standard50AP_GROUPINFO("SERNUM", 2, SLCAN::CANIface, _slcan_ser_port, -1),5152// @Param: TIMOUT53// @DisplayName: SLCAN Timeout54// @Description: Duration of inactivity after which SLCAN is switched back to original driver in seconds.55// @Range: 0 12756// @User: Standard57AP_GROUPINFO("TIMOUT", 3, SLCAN::CANIface, _slcan_timeout, 0),5859// @Param: SDELAY60// @DisplayName: SLCAN Start Delay61// @Description: Duration after which slcan starts after setting SERNUM in seconds.62// @Range: 0 12763// @User: Standard64AP_GROUPINFO("SDELAY", 4, SLCAN::CANIface, _slcan_start_delay, 1),6566AP_GROUPEND67};6869////////Helper Methods//////////7071static bool hex2nibble_error;7273static uint8_t nibble2hex(uint8_t x)74{75// Allocating in RAM because it's faster76static uint8_t ConversionTable[] = {77'0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F'78};79return ConversionTable[x & 0x0F];80}8182static uint8_t hex2nibble(char c)83{84uint8_t out = char_to_hex(c);8586if (out == 255) {87hex2nibble_error = true;88}89return out;90}9192bool SLCAN::CANIface::push_Frame(AP_HAL::CANFrame &frame)93{94AP_HAL::CANIface::CanRxItem frm;95frm.frame = frame;96frm.flags = 0;97frm.timestamp_us = AP_HAL::micros64();98return add_to_rx_queue(frm);99}100101/**102* General frame format:103* <type> <id> <dlc> <data>104* The emitting functions below are highly optimized for speed.105*/106bool SLCAN::CANIface::handle_FrameDataExt(const char* cmd, bool canfd)107{108AP_HAL::CANFrame f {};109hex2nibble_error = false;110f.canfd = canfd;111f.id = f.FlagEFF |112(hex2nibble(cmd[1]) << 28) |113(hex2nibble(cmd[2]) << 24) |114(hex2nibble(cmd[3]) << 20) |115(hex2nibble(cmd[4]) << 16) |116(hex2nibble(cmd[5]) << 12) |117(hex2nibble(cmd[6]) << 8) |118(hex2nibble(cmd[7]) << 4) |119(hex2nibble(cmd[8]) << 0);120f.dlc = hex2nibble(cmd[9]);121if (hex2nibble_error || f.dlc > (canfd?15:8)) {122return false;123}124{125const char* p = &cmd[10];126const uint8_t dlen = AP_HAL::CANFrame::dlcToDataLength(f.dlc);127for (unsigned i = 0; i < dlen; i++) {128f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));129p += 2;130}131}132if (hex2nibble_error) {133return false;134}135return push_Frame(f);136}137138/**139* General frame format:140* <type> <id> <dlc> <data>141* The emitting functions below are highly optimized for speed.142*/143bool SLCAN::CANIface::handle_FDFrameDataExt(const char* cmd)144{145#if HAL_CANFD_SUPPORTED146return false;147#else148AP_HAL::CANFrame f {};149hex2nibble_error = false;150f.canfd = true;151f.id = f.FlagEFF |152(hex2nibble(cmd[1]) << 28) |153(hex2nibble(cmd[2]) << 24) |154(hex2nibble(cmd[3]) << 20) |155(hex2nibble(cmd[4]) << 16) |156(hex2nibble(cmd[5]) << 12) |157(hex2nibble(cmd[6]) << 8) |158(hex2nibble(cmd[7]) << 4) |159(hex2nibble(cmd[8]) << 0);160f.dlc = hex2nibble(cmd[9]);161if (f.dlc > AP_HAL::CANFrame::dataLengthToDlc(AP_HAL::CANFrame::MaxDataLen)) {162return false;163}164{165const char* p = &cmd[10];166for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(f.dlc); i++) {167f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));168p += 2;169}170}171if (hex2nibble_error) {172return false;173}174return push_Frame(f);175#endif //#if HAL_CANFD_SUPPORTED176}177178bool SLCAN::CANIface::handle_FrameDataStd(const char* cmd)179{180AP_HAL::CANFrame f {};181hex2nibble_error = false;182f.id = (hex2nibble(cmd[1]) << 8) |183(hex2nibble(cmd[2]) << 4) |184(hex2nibble(cmd[3]) << 0);185if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {186return false;187}188f.dlc = cmd[4] - '0';189if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) {190return false;191}192{193const char* p = &cmd[5];194for (unsigned i = 0; i < f.dlc; i++) {195f.data[i] = (hex2nibble(*p) << 4) | hex2nibble(*(p + 1));196p += 2;197}198}199if (hex2nibble_error) {200return false;201}202return push_Frame(f);203}204205bool SLCAN::CANIface::handle_FrameRTRExt(const char* cmd)206{207AP_HAL::CANFrame f {};208hex2nibble_error = false;209f.id = f.FlagEFF | f.FlagRTR |210(hex2nibble(cmd[1]) << 28) |211(hex2nibble(cmd[2]) << 24) |212(hex2nibble(cmd[3]) << 20) |213(hex2nibble(cmd[4]) << 16) |214(hex2nibble(cmd[5]) << 12) |215(hex2nibble(cmd[6]) << 8) |216(hex2nibble(cmd[7]) << 4) |217(hex2nibble(cmd[8]) << 0);218if (cmd[9] < '0' || cmd[9] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {219return false;220}221f.dlc = cmd[9] - '0';222223if (f.dlc > AP_HAL::CANFrame::NonFDCANMaxDataLen) {224return false;225}226if (hex2nibble_error) {227return false;228}229return push_Frame(f);230}231232bool SLCAN::CANIface::handle_FrameRTRStd(const char* cmd)233{234AP_HAL::CANFrame f {};235hex2nibble_error = false;236f.id = f.FlagRTR |237(hex2nibble(cmd[1]) << 8) |238(hex2nibble(cmd[2]) << 4) |239(hex2nibble(cmd[3]) << 0);240if (cmd[4] < '0' || cmd[4] > ('0' + AP_HAL::CANFrame::NonFDCANMaxDataLen)) {241return false;242}243f.dlc = cmd[4] - '0';244if (f.dlc <= AP_HAL::CANFrame::NonFDCANMaxDataLen) {245return false;246}247if (hex2nibble_error) {248return false;249}250return push_Frame(f);251}252253static inline const char* getASCIIStatusCode(bool status)254{255return status ? "\r" : "\a";256}257258bool SLCAN::CANIface::init_passthrough(uint8_t i)259{260// we setup undelying can iface here which we use for passthrough261if (initialized_ ||262_slcan_can_port <= 0 ||263_slcan_can_port != i+1) {264return false;265}266267_can_iface = hal.can[i];268_iface_num = _slcan_can_port - 1;269_prev_ser_port = -1;270#if HAL_CANMANAGER_ENABLED271AP::can().log_text(AP_CANManager::LOG_INFO, LOG_TAG, "Setting SLCAN Passthrough for CAN%d\n", _slcan_can_port - 1);272#endif273return true;274}275276/**277* General frame format:278* <type> <id> <dlc> <data> [timestamp msec] [flags]279* Types:280* R - RTR extended281* r - RTR standard282* T - Data extended283* t - Data standard284* Flags:285* L - this frame is a loopback frame; timestamp field contains TX timestamp286*/287int16_t SLCAN::CANIface::reportFrame(const AP_HAL::CANFrame& frame, uint64_t timestamp_usec)288{289if (_port == nullptr) {290return -1;291}292#if HAL_CANFD_SUPPORTED293constexpr unsigned SLCANMaxFrameSize = 200;294#else295constexpr unsigned SLCANMaxFrameSize = 40;296#endif297uint8_t buffer[SLCANMaxFrameSize] = {'\0'};298uint8_t* p = &buffer[0];299/*300* Frame type301*/302if (frame.isRemoteTransmissionRequest()) {303*p++ = frame.isExtended() ? 'R' : 'r';304} else if (frame.isErrorFrame()) {305return -1; // Not supported306}307#if HAL_CANFD_SUPPORTED308else if (frame.canfd) {309*p++ = frame.isExtended() ? 'D' : 'd';310}311#endif312else {313*p++ = frame.isExtended() ? 'T' : 't';314}315316/*317* ID318*/319{320const uint32_t id = frame.id & frame.MaskExtID;321if (frame.isExtended()) {322*p++ = nibble2hex(id >> 28);323*p++ = nibble2hex(id >> 24);324*p++ = nibble2hex(id >> 20);325*p++ = nibble2hex(id >> 16);326*p++ = nibble2hex(id >> 12);327}328*p++ = nibble2hex(id >> 8);329*p++ = nibble2hex(id >> 4);330*p++ = nibble2hex(id >> 0);331}332333/*334* DLC335*/336*p++ = nibble2hex(frame.dlc);337338/*339* Data340*/341for (unsigned i = 0; i < AP_HAL::CANFrame::dlcToDataLength(frame.dlc); i++) {342const uint8_t byte = frame.data[i];343*p++ = nibble2hex(byte >> 4);344*p++ = nibble2hex(byte);345}346347/*348* Timestamp349*/350{351// SLCAN format - [0, 60000) milliseconds352const auto slcan_timestamp = uint16_t(timestamp_usec / 1000U);353*p++ = nibble2hex(slcan_timestamp >> 12);354*p++ = nibble2hex(slcan_timestamp >> 8);355*p++ = nibble2hex(slcan_timestamp >> 4);356*p++ = nibble2hex(slcan_timestamp >> 0);357}358359/*360* Finalization361*/362*p++ = '\r';363const auto frame_size = unsigned(p - &buffer[0]);364365if (_port->txspace() < frame_size) {366return 0;367}368//Write to Serial369if (!_port->write_locked(&buffer[0], frame_size, _serial_lock_key)) {370return 0;371}372return 1;373}374375//Accepts command string, returns response string or nullptr if no response is needed.376const char* SLCAN::CANIface::processCommand(char* cmd)377{378379if (_port == nullptr) {380return nullptr;381}382383/*384* High-traffic SLCAN commands go first385*/386if (cmd[0] == 'T' || cmd[0] == 'D') {387return handle_FrameDataExt(cmd, cmd[0]=='D') ? "Z\r" : "\a";388} else if (cmd[0] == 't') {389return handle_FrameDataStd(cmd) ? "z\r" : "\a";390} else if (cmd[0] == 'R') {391return handle_FrameRTRExt(cmd) ? "Z\r" : "\a";392} else if (cmd[0] == 'r' && cmd[1] <= '9') { // The second condition is needed to avoid greedy matching393// See long commands below394return handle_FrameRTRStd(cmd) ? "z\r" : "\a";395}396#if HAL_CANFD_SUPPORTED397else if (cmd[0] == 'D') {398return handle_FDFrameDataExt(cmd) ? "Z\r" : "\a";399}400#endif401402uint8_t resp_bytes[40];403uint16_t resp_len;404/*405* Regular SLCAN commands406*/407switch (cmd[0]) {408case 'S': // Set CAN bitrate409case 'O': // Open CAN in normal mode410case 'L': // Open CAN in listen-only mode411case 'l': // Open CAN with loopback enabled412case 'C': // Close CAN413case 'M': // Set CAN acceptance filter ID414case 'm': // Set CAN acceptance filter mask415case 'U': // Set UART baud rate, see http://www.can232.com/docs/can232_v3.pdf416case 'Z': { // Enable/disable RX and loopback timestamping417return getASCIIStatusCode(true); // Returning success for compatibility reasons418}419case 'F': { // Get status flags420resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes), "F%02X\r", unsigned(0)); // Returning success for compatibility reasons421if (resp_len > 0) {422_port->write_locked(resp_bytes, resp_len, _serial_lock_key);423}424return nullptr;425}426case 'V': { // HW/SW version427resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes),"V%x%x%x%x\r", 1, 0, 1, 0);428if (resp_len > 0) {429_port->write_locked(resp_bytes, resp_len, _serial_lock_key);430}431return nullptr;432}433case 'N': { // Serial number434const uint8_t uid_buf_len = 12;435uint8_t uid_len = uid_buf_len;436uint8_t unique_id[uid_buf_len];437char buf[uid_buf_len * 2 + 1] = {'\0'};438char* pos = &buf[0];439if (hal.util->get_system_id_unformatted(unique_id, uid_len)) {440for (uint8_t i = 0; i < uid_buf_len; i++) {441*pos++ = nibble2hex(unique_id[i] >> 4);442*pos++ = nibble2hex(unique_id[i]);443}444}445*pos++ = '\0';446resp_len = snprintf((char*)resp_bytes, sizeof(resp_bytes),"N%s\r", &buf[0]);447if (resp_len > 0) {448_port->write_locked(resp_bytes, resp_len, _serial_lock_key);449}450return nullptr;451}452default: {453break;454}455}456457return getASCIIStatusCode(false);458}459460// add bytes to parse the received SLCAN Data stream461inline void SLCAN::CANIface::addByte(const uint8_t byte)462{463if (_port == nullptr) {464return;465}466if ((byte >= 32 && byte <= 126)) { // Normal printable ASCII character467if (pos_ < SLCAN_BUFFER_SIZE) {468buf_[pos_] = char(byte);469pos_ += 1;470} else {471pos_ = 0; // Buffer overrun; silently drop the data472}473} else if (byte == '\r') { // End of command (SLCAN)474475// Processing the command476buf_[pos_] = '\0';477const char* const response = processCommand(reinterpret_cast<char*>(&buf_[0]));478pos_ = 0;479480// Sending the response if provided481if (response != nullptr) {482483_port->write_locked(reinterpret_cast<const uint8_t*>(response),484strlen(response), _serial_lock_key);485}486} else if (byte == 8 || byte == 127) { // DEL or BS (backspace)487if (pos_ > 0) {488pos_ -= 1;489}490} else { // This also includes Ctrl+C, Ctrl+D491pos_ = 0; // Invalid byte - drop the current command492}493}494495void SLCAN::CANIface::update_slcan_port()496{497const bool armed = hal.util->get_soft_armed();498if (_set_by_sermgr) {499if (armed && _port != nullptr) {500// auto-disable when armed501_port->lock_port(0, 0);502_port = nullptr;503_set_by_sermgr = false;504}505return;506}507if (_port == nullptr && !armed) {508_port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLCAN, 0);509if (_port != nullptr) {510_port->lock_port(_serial_lock_key, _serial_lock_key);511_set_by_sermgr = true;512return;513}514}515if (_prev_ser_port != _slcan_ser_port) {516if (!_slcan_start_req) {517_slcan_start_req_time = AP_HAL::millis();518_slcan_start_req = true;519}520if (((AP_HAL::millis() - _slcan_start_req_time) < ((uint32_t)_slcan_start_delay*1000))) {521return;522}523_port = AP::serialmanager().get_serial_by_id(_slcan_ser_port);524if (_port == nullptr) {525_slcan_ser_port.set_and_save(-1);526return;527}528_port->lock_port(_serial_lock_key, _serial_lock_key);529_prev_ser_port = _slcan_ser_port;530GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CANManager: Starting SLCAN Passthrough on Serial %d with CAN%d", _slcan_ser_port.get(), _iface_num);531_last_had_activity = AP_HAL::millis();532}533if (_port == nullptr) {534return;535}536if (((AP_HAL::millis() - _last_had_activity) > ((uint32_t)_slcan_timeout*1000)) &&537(uint32_t)_slcan_timeout != 0) {538_port->lock_port(0, 0);539_port = nullptr;540_slcan_ser_port.set_and_save(-1);541_prev_ser_port = -1;542_slcan_start_req = false;543}544}545546bool SLCAN::CANIface::set_event_handle(AP_HAL::BinarySemaphore *sem_handle)547{548// When in passthrough mode methods is handled through can iface549if (_can_iface) {550return _can_iface->set_event_handle(sem_handle);551}552return false;553}554555uint16_t SLCAN::CANIface::getNumFilters() const556{557// When in passthrough mode methods is handled through can iface558if (_can_iface) {559return _can_iface->getNumFilters();560}561return 0;562}563564uint32_t SLCAN::CANIface::getErrorCount() const565{566// When in passthrough mode methods is handled through can iface567if (_can_iface) {568return _can_iface->getErrorCount();569}570return 0;571}572573void SLCAN::CANIface::get_stats(ExpandingString &str)574{575// When in passthrough mode methods is handled through can iface576if (_can_iface) {577_can_iface->get_stats(str);578}579}580581bool SLCAN::CANIface::is_busoff() const582{583// When in passthrough mode methods is handled through can iface584if (_can_iface) {585return _can_iface->is_busoff();586}587return false;588}589590bool SLCAN::CANIface::configureFilters(const CanFilterConfig* filter_configs, uint16_t num_configs)591{592// When in passthrough mode methods is handled through can iface593if (_can_iface) {594return _can_iface->configureFilters(filter_configs, num_configs);595}596return true;597}598599void SLCAN::CANIface::flush_tx()600{601// When in passthrough mode methods is handled through can iface602if (_can_iface) {603_can_iface->flush_tx();604}605606if (_port) {607_port->flush();608}609}610611void SLCAN::CANIface::clear_rx()612{613// When in passthrough mode methods is handled through can iface614if (_can_iface) {615_can_iface->clear_rx();616}617rx_queue_.clear();618}619620bool SLCAN::CANIface::is_initialized() const621{622// When in passthrough mode methods is handled through can iface623if (_can_iface) {624return _can_iface->is_initialized();625}626return false;627}628629bool SLCAN::CANIface::select(bool &read, bool &write, const AP_HAL::CANFrame* const pending_tx,630uint64_t blocking_deadline)631{632update_slcan_port();633bool ret = false;634// When in passthrough mode select is handled through can iface635if (_can_iface) {636ret = _can_iface->select(read, write, pending_tx, blocking_deadline);637}638639if (_port == nullptr) {640return ret;641}642643// ensure we own the UART. Locking is handled at the CAN interface level644_port->begin_locked(0, 0, 0, _serial_lock_key);645646// if under passthrough, we only do send when can_iface also allows it647if (_port->available_locked(_serial_lock_key) || rx_queue_.available()) {648// allow for receiving messages over slcan649read = true;650ret = true;651}652653return ret;654}655656657// send method to transmit the frame through SLCAN interface658int16_t SLCAN::CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, AP_HAL::CANIface::CanIOFlags flags)659{660update_slcan_port();661int16_t ret = 0;662// When in passthrough mode select is handled through can iface663if (_can_iface) {664ret = _can_iface->send(frame, tx_deadline, flags);665}666667if (_port == nullptr) {668return ret;669}670671if (frame.isErrorFrame()672#if !HAL_CANFD_SUPPORTED673|| frame.dlc > 8674#endif675) {676return ret;677}678reportFrame(frame, AP_HAL::micros64());679return ret;680}681682// receive method to read the frame recorded in the buffer683int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time,684AP_HAL::CANIface::CanIOFlags& out_flags)685{686update_slcan_port();687// When in passthrough mode select is handled through can iface688if (_can_iface) {689int16_t ret = _can_iface->receive(out_frame, rx_time, out_flags);690if (ret > 0) {691// we also pass this frame through to slcan iface,692// and immediately return693reportFrame(out_frame, AP_HAL::micros64());694return ret;695} else if (ret < 0) {696return ret;697}698}699700// We found nothing in HAL's CANIface receive, so look in SLCANIface701if (_port == nullptr) {702return 0;703}704705if (_port->available_locked(_serial_lock_key)) {706uint32_t num_bytes = _port->available_locked(_serial_lock_key);707// flush bytes from port708while (num_bytes--) {709uint8_t b;710if (_port->read_locked(&b, 1, _serial_lock_key) != 1) {711break;712}713addByte(b);714if (!rx_queue_.space()) {715break;716}717}718}719if (rx_queue_.available()) {720// if we already have something in buffer transmit it721CanRxItem frm;722if (!rx_queue_.peek(frm)) {723return 0;724}725out_frame = frm.frame;726rx_time = frm.timestamp_us;727out_flags = frm.flags;728_last_had_activity = AP_HAL::millis();729// Also send this frame over can_iface when in passthrough mode,730// We just push this frame without caring for priority etc731if (_can_iface) {732bool read = false;733bool write = true;734_can_iface->select(read, write, &out_frame, 0); // select without blocking735if (write && _can_iface->send(out_frame, AP_HAL::micros64() + 100000, out_flags) == 1) {736rx_queue_.pop();737num_tries = 0;738} else if (num_tries > 8) {739rx_queue_.pop();740num_tries = 0;741} else {742num_tries++;743}744} else {745// we just throw away frames if we don't746// have any can iface to pass through to747rx_queue_.pop();748}749return 1;750}751return 0;752}753754void SLCAN::CANIface::reset_params()755{756_slcan_ser_port.set_and_save(-1);757}758#endif // AP_CAN_SLCAN_ENABLED759760761