Path: blob/master/libraries/AP_DDS/AP_DDS_Serial.cpp
9417 views
#include "AP_DDS_Client.h"12#if AP_DDS_ENABLED34#include <AP_SerialManager/AP_SerialManager.h>56#include <errno.h>78/*9open connection on a serial port10*/11bool AP_DDS_Client::serial_transport_open(uxrCustomTransport *t)12{13AP_DDS_Client *dds = (AP_DDS_Client *)t->args;14AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();15auto *dds_port = serial_manager->find_serial(AP_SerialManager::SerialProtocol_DDS_XRCE, 0);16if (dds_port == nullptr) {17return false;18}19// ensure we own the UART20dds_port->begin(0);21dds->serial.port = dds_port;22return true;23}2425/*26close serial transport27*/28bool AP_DDS_Client::serial_transport_close(uxrCustomTransport *t)29{30// we don't actually close the UART31return true;32}3334/*35write on serial transport36*/37size_t AP_DDS_Client::serial_transport_write(uxrCustomTransport *t, const uint8_t* buf, size_t len, uint8_t* error)38{39AP_DDS_Client *dds = (AP_DDS_Client *)t->args;40if (dds->serial.port == nullptr) {41*error = EINVAL;42return 0;43}44ssize_t bytes_written = dds->serial.port->write(buf, len);45if (bytes_written <= 0) {46*error = 1;47return 0;48}49//! @todo populate the error code correctly50*error = 0;51return bytes_written;52}5354/*55read from a serial transport56*/57size_t AP_DDS_Client::serial_transport_read(uxrCustomTransport *t, uint8_t* buf, size_t len, int timeout_ms, uint8_t* error)58{59AP_DDS_Client *dds = (AP_DDS_Client *)t->args;60if (dds->serial.port == nullptr) {61*error = EINVAL;62return 0;63}64const uint32_t tstart = AP_HAL::millis();65while (AP_HAL::millis() - tstart < uint32_t(timeout_ms) &&66dds->serial.port->available() < len) {67hal.scheduler->delay_microseconds(100); // TODO select or poll this is limiting speed (100us)68}69ssize_t bytes_read = dds->serial.port->read(buf, len);70if (bytes_read <= 0) {71*error = 1;72return 0;73}74//! @todo Add error reporting75*error = 0;76return bytes_read;77}7879/*80initialise serial connection81*/82bool AP_DDS_Client::ddsSerialInit()83{84// setup a framed transport for serial85uxr_set_custom_transport_callbacks(&serial.transport, true,86serial_transport_open,87serial_transport_close,88serial_transport_write,89serial_transport_read);9091if (!uxr_init_custom_transport(&serial.transport, (void*)this)) {92return false;93}94comm = &serial.transport.comm;95return true;96}97#endif // AP_DDS_ENABLED9899