Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DDS/AP_DDS_Serial.cpp
9417 views
1
#include "AP_DDS_Client.h"
2
3
#if AP_DDS_ENABLED
4
5
#include <AP_SerialManager/AP_SerialManager.h>
6
7
#include <errno.h>
8
9
/*
10
open connection on a serial port
11
*/
12
bool AP_DDS_Client::serial_transport_open(uxrCustomTransport *t)
13
{
14
AP_DDS_Client *dds = (AP_DDS_Client *)t->args;
15
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
16
auto *dds_port = serial_manager->find_serial(AP_SerialManager::SerialProtocol_DDS_XRCE, 0);
17
if (dds_port == nullptr) {
18
return false;
19
}
20
// ensure we own the UART
21
dds_port->begin(0);
22
dds->serial.port = dds_port;
23
return true;
24
}
25
26
/*
27
close serial transport
28
*/
29
bool AP_DDS_Client::serial_transport_close(uxrCustomTransport *t)
30
{
31
// we don't actually close the UART
32
return true;
33
}
34
35
/*
36
write on serial transport
37
*/
38
size_t AP_DDS_Client::serial_transport_write(uxrCustomTransport *t, const uint8_t* buf, size_t len, uint8_t* error)
39
{
40
AP_DDS_Client *dds = (AP_DDS_Client *)t->args;
41
if (dds->serial.port == nullptr) {
42
*error = EINVAL;
43
return 0;
44
}
45
ssize_t bytes_written = dds->serial.port->write(buf, len);
46
if (bytes_written <= 0) {
47
*error = 1;
48
return 0;
49
}
50
//! @todo populate the error code correctly
51
*error = 0;
52
return bytes_written;
53
}
54
55
/*
56
read from a serial transport
57
*/
58
size_t AP_DDS_Client::serial_transport_read(uxrCustomTransport *t, uint8_t* buf, size_t len, int timeout_ms, uint8_t* error)
59
{
60
AP_DDS_Client *dds = (AP_DDS_Client *)t->args;
61
if (dds->serial.port == nullptr) {
62
*error = EINVAL;
63
return 0;
64
}
65
const uint32_t tstart = AP_HAL::millis();
66
while (AP_HAL::millis() - tstart < uint32_t(timeout_ms) &&
67
dds->serial.port->available() < len) {
68
hal.scheduler->delay_microseconds(100); // TODO select or poll this is limiting speed (100us)
69
}
70
ssize_t bytes_read = dds->serial.port->read(buf, len);
71
if (bytes_read <= 0) {
72
*error = 1;
73
return 0;
74
}
75
//! @todo Add error reporting
76
*error = 0;
77
return bytes_read;
78
}
79
80
/*
81
initialise serial connection
82
*/
83
bool AP_DDS_Client::ddsSerialInit()
84
{
85
// setup a framed transport for serial
86
uxr_set_custom_transport_callbacks(&serial.transport, true,
87
serial_transport_open,
88
serial_transport_close,
89
serial_transport_write,
90
serial_transport_read);
91
92
if (!uxr_init_custom_transport(&serial.transport, (void*)this)) {
93
return false;
94
}
95
comm = &serial.transport.comm;
96
return true;
97
}
98
#endif // AP_DDS_ENABLED
99