Path: blob/master/Tools/AP_Periph/serial_tunnel.cpp
9377 views
/*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#if AP_PERIPH_GPS_ENABLED46if (uart_num == -1) {47uart_num = g.gps_port;48}49#endif50#if AP_PERIPH_RANGEFINDER_ENABLED51if (uart_num == -1) {52uart_num = g.rangefinder_port[0];53}54#endif55#if AP_PERIPH_ADSB_ENABLED56if (uart_num == -1) {57uart_num = g.adsb_port;58}59#endif60#if AP_PERIPH_PROXIMITY_ENABLED61if (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}80int8_t uart_num = pkt.serial_id;81if (uart_num == -1) {82uart_num = get_default_tunnel_serial_port();83}84if (uart_num < 0) {85return;86}87if (uint8_t(uart_num) > ARRAY_SIZE(uart_monitors)) {88return;89}90auto &uart_monitor = uart_monitors[uart_num];91if (uart_monitor.uart == nullptr) {92auto *uart = hal.serial(uart_num);93if (uart == nullptr) {94return;95}96if (uart_monitor.buffer == nullptr) {97uart_monitor.buffer = NEW_NOTHROW ByteBuffer(1024);98if (uart_monitor.buffer == nullptr) {99return;100}101uart_monitor.uart_num = uart_num;102}103uart_monitor.baudrate = 0;104uart_monitor.uart = uart; // setting this indicates the monitor is set up105uart_monitor.uart->set_monitor_read_buffer(uart_monitor.buffer);106}107if (uart_monitor.uart == nullptr) {108return;109}110/*111allow for locked state to change at any time, so users can112switch between locked and unlocked while connected113*/114const bool was_locked = uart_monitor.locked;115uart_monitor.locked = (pkt.options & UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT) != 0;116if (uart_monitor.locked) {117uart_monitor.uart->lock_port(TUNNEL_LOCK_KEY, TUNNEL_LOCK_KEY);118} else {119uart_monitor.uart->lock_port(0,0);120}121uart_monitor.node_id = transfer->source_node_id;122uart_monitor.protocol = pkt.protocol.protocol;123if (pkt.baudrate != uart_monitor.baudrate || !was_locked) {124if (uart_monitor.locked && pkt.baudrate != 0) {125// ensure we have enough buffer space for a uBlox fw update and fast uCenter data126uart_monitor.uart->begin_locked(pkt.baudrate, 2048, 2048, TUNNEL_LOCK_KEY);127debug("begin_locked %u", unsigned(pkt.baudrate));128}129uart_monitor.baudrate = pkt.baudrate;130}131uart_monitor.last_request_ms = AP_HAL::millis();132133// write to device134if (pkt.buffer.len > 0) {135if (uart_monitor.locked) {136debug("write_locked %u", unsigned(pkt.buffer.len));137uart_monitor.uart->write_locked(pkt.buffer.data, pkt.buffer.len, TUNNEL_LOCK_KEY);138} else {139uart_monitor.uart->write(pkt.buffer.data, pkt.buffer.len);140}141} else {142debug("locked keepalive");143}144}145146/*147send tunnelled serial data148*/149void AP_Periph_FW::send_serial_monitor_data()150{151for (auto &m : uart_monitors) {152send_serial_monitor_data_instance(m);153}154}155156void AP_Periph_FW::send_serial_monitor_data_instance(AP_Periph_FW::UARTMonitor &uart_monitor)157{158if (uart_monitor.uart == nullptr ||159uart_monitor.node_id == 0 ||160uart_monitor.buffer == nullptr) {161return;162}163const uint32_t last_req_ms = uart_monitor.last_request_ms;164const uint32_t now_ms = AP_HAL::millis();165if (now_ms - last_req_ms >= 3000) {166// stop sending and unlock, but don't release the buffer167if (uart_monitor.locked) {168debug("unlock");169uart_monitor.uart->lock_port(0, 0);170}171uart_monitor.uart = nullptr;172return;173}174if (uart_monitor.locked) {175/*176when the port is locked nobody is reading the uart so the177monitor doesn't fill. We read here to ensure it fills178*/179uint8_t buf[120];180for (uint8_t i=0; i<8; i++) {181if (uart_monitor.uart->read_locked(buf, sizeof(buf), TUNNEL_LOCK_KEY) <= 0) {182break;183}184}185}186uint8_t sends = 8;187while (uart_monitor.buffer->available() > 0 && sends-- > 0) {188uint32_t n;189const uint8_t *buf = uart_monitor.buffer->readptr(n);190if (n == 0) {191return;192}193// broadcast data as tunnel packets, can be used for uCenter debug and device fw update194uavcan_tunnel_Targetted pkt {};195n = MIN(n, sizeof(pkt.buffer.data));196pkt.target_node = uart_monitor.node_id;197pkt.protocol.protocol = uart_monitor.protocol;198pkt.buffer.len = n;199pkt.baudrate = uart_monitor.baudrate;200pkt.serial_id = uart_monitor.uart_num;201memcpy(pkt.buffer.data, buf, n);202203uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE];204const uint16_t total_size = uavcan_tunnel_Targetted_encode(&pkt, buffer, !canfdout());205206debug("read %u", unsigned(n));207208if (!canard_broadcast(UAVCAN_TUNNEL_TARGETTED_SIGNATURE,209UAVCAN_TUNNEL_TARGETTED_ID,210CANARD_TRANSFER_PRIORITY_MEDIUM,211&buffer[0],212total_size)) {213break;214}215uart_monitor.buffer->advance(n);216}217}218#endif // AP_UART_MONITOR_ENABLED219220221