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/Tools/AP_Periph/serial_tunnel.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15handle tunnelling of serial data over DroneCAN16*/1718#include <AP_HAL/AP_HAL_Boards.h>19#include "AP_Periph.h"2021#if AP_UART_MONITOR_ENABLED2223#include <dronecan_msgs.h>2425extern const AP_HAL::HAL &hal;2627#define TUNNEL_LOCK_KEY 0xf2e460e4U2829#ifndef TUNNEL_DEBUG30#define TUNNEL_DEBUG 031#endif3233#if TUNNEL_DEBUG34# define debug(fmt, args...) can_printf(fmt "\n", ##args)35#else36# define debug(fmt, args...)37#endif3839/*40get the default port to tunnel if the client requests port -141*/42int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const43{44int8_t uart_num = -1;45#ifdef HAL_PERIPH_ENABLE_GPS46if (uart_num == -1) {47uart_num = g.gps_port;48}49#endif50#ifdef HAL_PERIPH_ENABLE_RANGEFINDER51if (uart_num == -1) {52uart_num = g.rangefinder_port[0];53}54#endif55#ifdef HAL_PERIPH_ENABLE_ADSB56if (uart_num == -1) {57uart_num = g.adsb_port;58}59#endif60#ifdef HAL_PERIPH_ENABLE_PROXIMITY61if (uart_num == -1) {62uart_num = g.proximity_port;63}64#endif65return uart_num;66}6768/*69handle tunnel data70*/71void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* canard_ins, CanardRxTransfer* transfer)72{73uavcan_tunnel_Targetted pkt;74if (uavcan_tunnel_Targetted_decode(transfer, &pkt)) {75return;76}77if (pkt.target_node != canardGetLocalNodeID(canard_ins)) {78return;79}80if (uart_monitor.buffer == nullptr) {81uart_monitor.buffer = NEW_NOTHROW ByteBuffer(1024);82if (uart_monitor.buffer == nullptr) {83return;84}85}86int8_t uart_num = pkt.serial_id;87if (uart_num == -1) {88uart_num = get_default_tunnel_serial_port();89}90if (uart_num < 0) {91return;92}93auto *uart = hal.serial(uart_num);94if (uart == nullptr) {95return;96}97if (uart_monitor.uart_num != uart_num && uart_monitor.uart != nullptr) {98// remove monitor from previous uart99hal.serial(uart_monitor.uart_num)->set_monitor_read_buffer(nullptr);100}101uart_monitor.uart_num = uart_num;102if (uart != uart_monitor.uart) {103// change of uart or expired, clear old data104uart_monitor.buffer->clear();105uart_monitor.uart = uart;106uart_monitor.baudrate = 0;107}108if (uart_monitor.uart == nullptr) {109return;110}111/*112allow for locked state to change at any time, so users can113switch between locked and unlocked while connected114*/115const bool was_locked = uart_monitor.locked;116uart_monitor.locked = (pkt.options & UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT) != 0;117if (uart_monitor.locked) {118uart_monitor.uart->lock_port(TUNNEL_LOCK_KEY, TUNNEL_LOCK_KEY);119} else {120uart_monitor.uart->lock_port(0,0);121}122uart_monitor.node_id = transfer->source_node_id;123uart_monitor.protocol = pkt.protocol.protocol;124if (pkt.baudrate != uart_monitor.baudrate || !was_locked) {125if (uart_monitor.locked && pkt.baudrate != 0) {126// ensure we have enough buffer space for a uBlox fw update and fast uCenter data127uart_monitor.uart->begin_locked(pkt.baudrate, 2048, 2048, TUNNEL_LOCK_KEY);128debug("begin_locked %u", unsigned(pkt.baudrate));129}130uart_monitor.baudrate = pkt.baudrate;131}132uart_monitor.uart->set_monitor_read_buffer(uart_monitor.buffer);133uart_monitor.last_request_ms = AP_HAL::millis();134135// write to device136if (pkt.buffer.len > 0) {137if (uart_monitor.locked) {138debug("write_locked %u", unsigned(pkt.buffer.len));139uart_monitor.uart->write_locked(pkt.buffer.data, pkt.buffer.len, TUNNEL_LOCK_KEY);140} else {141uart_monitor.uart->write(pkt.buffer.data, pkt.buffer.len);142}143} else {144debug("locked keepalive");145}146}147148/*149send tunnelled serial data150*/151void AP_Periph_FW::send_serial_monitor_data()152{153if (uart_monitor.uart == nullptr ||154uart_monitor.node_id == 0 ||155uart_monitor.buffer == nullptr) {156return;157}158const uint32_t last_req_ms = uart_monitor.last_request_ms;159const uint32_t now_ms = AP_HAL::millis();160if (now_ms - last_req_ms >= 3000) {161// stop sending and unlock, but don't release the buffer162if (uart_monitor.locked) {163debug("unlock");164uart_monitor.uart->lock_port(0, 0);165}166uart_monitor.uart = nullptr;167return;168}169if (uart_monitor.locked) {170/*171when the port is locked nobody is reading the uart so the172monitor doesn't fill. We read here to ensure it fills173*/174uint8_t buf[120];175for (uint8_t i=0; i<8; i++) {176if (uart_monitor.uart->read_locked(buf, sizeof(buf), TUNNEL_LOCK_KEY) <= 0) {177break;178}179}180}181uint8_t sends = 8;182while (uart_monitor.buffer->available() > 0 && sends-- > 0) {183uint32_t n;184const uint8_t *buf = uart_monitor.buffer->readptr(n);185if (n == 0) {186return;187}188// broadcast data as tunnel packets, can be used for uCenter debug and device fw update189uavcan_tunnel_Targetted pkt {};190n = MIN(n, sizeof(pkt.buffer.data));191pkt.target_node = uart_monitor.node_id;192pkt.protocol.protocol = uart_monitor.protocol;193pkt.buffer.len = n;194pkt.baudrate = uart_monitor.baudrate;195pkt.serial_id = uart_monitor.uart_num;196memcpy(pkt.buffer.data, buf, n);197198uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE];199const uint16_t total_size = uavcan_tunnel_Targetted_encode(&pkt, buffer, !canfdout());200201debug("read %u", unsigned(n));202203if (!canard_broadcast(UAVCAN_TUNNEL_TARGETTED_SIGNATURE,204UAVCAN_TUNNEL_TARGETTED_ID,205CANARD_TRANSFER_PRIORITY_MEDIUM,206&buffer[0],207total_size)) {208break;209}210uart_monitor.buffer->advance(n);211}212}213#endif // AP_UART_MONITOR_ENABLED214215216