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_DroneCAN/AP_DroneCAN_serial.cpp
Views: 1798
/*1map local serial ports to remote DroneCAN serial ports using the2TUNNEL_TARGETTED message3*/45#include "AP_DroneCAN.h"67#if HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED89#include <AP_Math/AP_Math.h>10#include <AP_BoardConfig/AP_BoardConfig.h>1112AP_DroneCAN_Serial *AP_DroneCAN_Serial::serial[HAL_MAX_CAN_PROTOCOL_DRIVERS];1314#ifndef AP_DRONECAN_SERIAL_MIN_TXSIZE15#define AP_DRONECAN_SERIAL_MIN_TXSIZE 204816#endif1718#ifndef AP_DRONECAN_SERIAL_MIN_RXSIZE19#define AP_DRONECAN_SERIAL_MIN_RXSIZE 204820#endif2122/*23initialise DroneCAN serial aports24*/25void AP_DroneCAN_Serial::init(AP_DroneCAN *_dronecan)26{27if (enable == 0) {28return;29}30const uint8_t driver_index = _dronecan->get_driver_index();31if (driver_index >= ARRAY_SIZE(serial)) {32return;33}34serial[driver_index] = this;35dronecan = _dronecan;3637const uint8_t base_port = driver_index == 0? AP_SERIALMANAGER_CAN_D1_PORT_1 : AP_SERIALMANAGER_CAN_D2_PORT_1;38bool need_subscriber = false;3940for (uint8_t i=0; i<ARRAY_SIZE(ports); i++) {41auto &p = ports[i];42p.state.idx = base_port + i;43if (p.node > 0 && p.idx >= 0) {44p.init();45AP::serialmanager().register_port(&p);46need_subscriber = true;47}48}4950if (need_subscriber) {51if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) {52AP_BoardConfig::allocation_error("serial_tunnel_sub");53}54targetted = NEW_NOTHROW Canard::Publisher<uavcan_tunnel_Targetted>(dronecan->get_canard_iface());55if (targetted == nullptr) {56AP_BoardConfig::allocation_error("serial_tunnel_pub");57}58targetted->set_timeout_ms(20);59targetted->set_priority(CANARD_TRANSFER_PRIORITY_MEDIUM);60}61}6263/*64update DroneCAN serial ports65*/66void AP_DroneCAN_Serial::update(void)67{68const uint32_t now_ms = AP_HAL::millis();69for (auto &p : ports) {70if (p.baudrate == 0) {71continue;72}73if (p.writebuffer == nullptr || p.node <= 0 || p.idx < 0) {74continue;75}76uavcan_tunnel_Targetted pkt {};77uint32_t n = 0;78{79WITH_SEMAPHORE(p.sem);80uint32_t avail;81const bool send_keepalive = now_ms - p.last_send_ms > 500;82const auto *ptr = p.writebuffer->readptr(avail);83if (!send_keepalive && (ptr == nullptr || avail <= 0)) {84continue;85}86n = MIN(avail, sizeof(pkt.buffer.data));87pkt.target_node = p.node;88switch (p.state.protocol) {89case AP_SerialManager::SerialProtocol_MAVLink:90pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK;91break;92case AP_SerialManager::SerialProtocol_MAVLink2:93pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_MAVLINK2;94break;95case AP_SerialManager::SerialProtocol_GPS:96case AP_SerialManager::SerialProtocol_GPS2: // is not in SERIAL1_PROTOCOL option list, but could be entered by user97pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_GPS_GENERIC;98break;99default:100pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED;101}102pkt.buffer.len = n;103pkt.baudrate = p.baudrate;104pkt.serial_id = p.idx;105pkt.options = UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT;106if (ptr != nullptr) {107memcpy(pkt.buffer.data, ptr, n);108}109}110if (targetted->broadcast(pkt)) {111WITH_SEMAPHORE(p.sem);112p.writebuffer->advance(n);113p.last_send_ms = now_ms;114}115}116}117118/*119handle incoming tunnel serial packet120*/121void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan,122const CanardRxTransfer& transfer,123const uavcan_tunnel_Targetted &msg)124{125uint8_t driver_index = dronecan->get_driver_index();126if (driver_index >= ARRAY_SIZE(serial) || serial[driver_index] == nullptr) {127return;128}129auto &s = *serial[driver_index];130for (auto &p : s.ports) {131if (p.idx == msg.serial_id && transfer.source_node_id == p.node) {132WITH_SEMAPHORE(p.sem);133if (p.readbuffer != nullptr) {134p.readbuffer->write(msg.buffer.data, msg.buffer.len);135p.last_recv_us = AP_HAL::micros64();136}137break;138}139}140}141142/*143initialise port144*/145void AP_DroneCAN_Serial::Port::init(void)146{147baudrate = AP_SerialManager::map_baudrate(state.baud);148begin(baudrate, 0, 0);149}150151/*152available space in outgoing buffer153*/154uint32_t AP_DroneCAN_Serial::Port::txspace(void)155{156WITH_SEMAPHORE(sem);157return writebuffer != nullptr ? writebuffer->space() : 0;158}159160void AP_DroneCAN_Serial::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS)161{162rxS = MAX(rxS, AP_DRONECAN_SERIAL_MIN_RXSIZE);163txS = MAX(txS, AP_DRONECAN_SERIAL_MIN_TXSIZE);164init_buffers(rxS, txS);165if (b != 0) {166baudrate = b;167}168}169170size_t AP_DroneCAN_Serial::Port::_write(const uint8_t *buffer, size_t size)171{172WITH_SEMAPHORE(sem);173return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0;174}175176ssize_t AP_DroneCAN_Serial::Port::_read(uint8_t *buffer, uint16_t count)177{178WITH_SEMAPHORE(sem);179return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1;180}181182uint32_t AP_DroneCAN_Serial::Port::_available()183{184WITH_SEMAPHORE(sem);185return readbuffer != nullptr ? readbuffer->available() : 0;186}187188189bool AP_DroneCAN_Serial::Port::_discard_input()190{191WITH_SEMAPHORE(sem);192if (readbuffer != nullptr) {193readbuffer->clear();194}195return true;196}197198/*199initialise read/write buffers200*/201bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx)202{203if (size_tx == last_size_tx &&204size_rx == last_size_rx) {205return true;206}207WITH_SEMAPHORE(sem);208if (readbuffer == nullptr) {209readbuffer = NEW_NOTHROW ByteBuffer(size_rx);210} else {211readbuffer->set_size_best(size_rx);212}213if (writebuffer == nullptr) {214writebuffer = NEW_NOTHROW ByteBuffer(size_tx);215} else {216writebuffer->set_size_best(size_tx);217}218last_size_rx = size_rx;219last_size_tx = size_tx;220return readbuffer != nullptr && writebuffer != nullptr;221}222223/*224return timestamp estimate in microseconds for when the start of225a nbytes packet arrived on the uart.226*/227uint64_t AP_DroneCAN_Serial::Port::receive_time_constraint_us(uint16_t nbytes)228{229WITH_SEMAPHORE(sem);230uint64_t last_receive_us = last_recv_us;231if (baudrate > 0) {232// assume 10 bits per byte.233uint32_t transport_time_us = (1000000UL * 10UL / baudrate) * (nbytes+available());234last_receive_us -= transport_time_us;235}236return last_receive_us;237}238239#endif // HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED240241242