Path: blob/master/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp
9744 views
/*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.tx_stats_bytes += n;114p.last_send_ms = now_ms;115}116}117}118119/*120handle incoming tunnel serial packet121*/122void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan,123const CanardRxTransfer& transfer,124const uavcan_tunnel_Targetted &msg)125{126uint8_t driver_index = dronecan->get_driver_index();127if (driver_index >= ARRAY_SIZE(serial) || serial[driver_index] == nullptr) {128return;129}130auto &s = *serial[driver_index];131for (auto &p : s.ports) {132if (p.idx == msg.serial_id && transfer.source_node_id == p.node) {133WITH_SEMAPHORE(p.sem);134if (p.readbuffer != nullptr) {135const uint32_t written = p.readbuffer->write(msg.buffer.data, msg.buffer.len);136p.rx_stats_bytes += msg.buffer.len;137p.rx_stats_dropped_bytes += msg.buffer.len - written;138p.last_recv_us = AP_HAL::micros64();139}140break;141}142}143}144145/*146initialise port147*/148void AP_DroneCAN_Serial::Port::init(void)149{150baudrate = AP_SerialManager::map_baudrate(state.baud);151begin(baudrate, 0, 0);152}153154/*155available space in outgoing buffer156*/157uint32_t AP_DroneCAN_Serial::Port::txspace(void)158{159WITH_SEMAPHORE(sem);160return writebuffer != nullptr ? writebuffer->space() : 0;161}162163void AP_DroneCAN_Serial::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS)164{165rxS = MAX(rxS, AP_DRONECAN_SERIAL_MIN_RXSIZE);166txS = MAX(txS, AP_DRONECAN_SERIAL_MIN_TXSIZE);167init_buffers(rxS, txS);168if (b != 0) {169baudrate = b;170}171}172173size_t AP_DroneCAN_Serial::Port::_write(const uint8_t *buffer, size_t size)174{175WITH_SEMAPHORE(sem);176return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0;177}178179ssize_t AP_DroneCAN_Serial::Port::_read(uint8_t *buffer, uint16_t count)180{181WITH_SEMAPHORE(sem);182return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1;183}184185uint32_t AP_DroneCAN_Serial::Port::_available()186{187WITH_SEMAPHORE(sem);188return readbuffer != nullptr ? readbuffer->available() : 0;189}190191192bool AP_DroneCAN_Serial::Port::_discard_input()193{194WITH_SEMAPHORE(sem);195if (readbuffer != nullptr) {196rx_stats_dropped_bytes += readbuffer->available();197readbuffer->clear();198}199return true;200}201202/*203initialise read/write buffers204*/205bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx)206{207if (size_tx == last_size_tx &&208size_rx == last_size_rx) {209return true;210}211WITH_SEMAPHORE(sem);212if (readbuffer == nullptr) {213readbuffer = NEW_NOTHROW ByteBuffer(size_rx);214} else {215readbuffer->set_size_best(size_rx);216}217if (writebuffer == nullptr) {218writebuffer = NEW_NOTHROW ByteBuffer(size_tx);219} else {220writebuffer->set_size_best(size_tx);221}222last_size_rx = size_rx;223last_size_tx = size_tx;224return readbuffer != nullptr && writebuffer != nullptr;225}226227/*228return timestamp estimate in microseconds for when the start of229a nbytes packet arrived on the uart.230*/231uint64_t AP_DroneCAN_Serial::Port::receive_time_constraint_us(uint16_t nbytes)232{233WITH_SEMAPHORE(sem);234uint64_t last_receive_us = last_recv_us;235if (baudrate > 0) {236// assume 10 bits per byte.237uint32_t transport_time_us = (1000000UL * 10UL / baudrate) * (nbytes+available());238last_receive_us -= transport_time_us;239}240return last_receive_us;241}242243#endif // HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED244245246