Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

DroneCAN: serial over CAN backport for 4.4.x #25599

Open
wants to merge 2 commits into
base: Plane-4.4
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
104 changes: 94 additions & 10 deletions libraries/AP_SerialManager/AP_SerialManager.cpp
Expand Up @@ -397,6 +397,8 @@ void AP_SerialManager::init()
for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
auto *uart = hal.serial(i);

state[i].idx = i;

if (uart != nullptr) {
set_options(i);
switch (state[i].protocol) {
Expand Down Expand Up @@ -547,6 +549,17 @@ const AP_SerialManager::UARTState *AP_SerialManager::find_protocol_instance(enum
}
}

#if AP_SERIALMANAGER_REGISTER_ENABLED
for (auto p = registered_ports; p; p = p->next) {
if (protocol_match(protocol, (enum SerialProtocol)p->state.protocol.get())) {
if (found_instance == instance) {
return &p->state;
}
found_instance++;
}
}
#endif

// if we got this far we did not find the uart
return nullptr;
}
Expand All @@ -560,10 +573,23 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
if (_state == nullptr) {
return nullptr;
}
const uint8_t serial_idx = _state - &state[0];
const uint8_t serial_idx = _state->idx;

// set options before any user does begin()
AP_HAL::UARTDriver *port = hal.serial(serial_idx);

#if AP_SERIALMANAGER_REGISTER_ENABLED
if (port == nullptr) {
// look for a registered port
for (auto p = registered_ports; p; p = p->next) {
if (p->state.idx == serial_idx) {
port = p;
break;
}
}
}
#endif

if (port) {
port->set_options(_state->options);
}
Expand Down Expand Up @@ -595,7 +621,7 @@ int8_t AP_SerialManager::find_portnum(enum SerialProtocol protocol, uint8_t inst
if (_state == nullptr) {
return -1;
}
return int8_t(_state - &state[0]);
return int8_t(_state->idx);
}

// get_serial_by_id - gets serial by serial id
Expand All @@ -604,6 +630,13 @@ AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id)
if (id < SERIALMANAGER_NUM_PORTS) {
return hal.serial(id);
}
#if AP_SERIALMANAGER_REGISTER_ENABLED
for (auto p = registered_ports; p; p = p->next) {
if (p->state.idx == id) {
return (AP_HAL::UARTDriver *)p;
}
}
#endif
return nullptr;
}

Expand All @@ -619,6 +652,24 @@ void AP_SerialManager::set_blocking_writes_all(bool blocking)
}
}

/*
get a UARTState by index
*/
const AP_SerialManager::UARTState *AP_SerialManager::get_state_by_id(uint8_t id) const
{
if (id < SERIALMANAGER_NUM_PORTS) {
return &state[id];
}
#if AP_SERIALMANAGER_REGISTER_ENABLED
for (auto p = registered_ports; p; p = p->next) {
if (p->state.idx == id) {
return &p->state;
}
}
#endif
return nullptr;
}

/*
* map from a 16 bit EEPROM baud rate to a real baud rate. For
* stm32-based boards we can do 1.5MBit, although 921600 is more
Expand Down Expand Up @@ -694,18 +745,24 @@ void AP_SerialManager::set_options(uint16_t i)

// get the passthru ports if enabled
bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s,
uint32_t &baud1, uint32_t &baud2) const
uint32_t &baud1, uint32_t &baud2)
{
if (passthru_port2 < 0 ||
passthru_port2 >= SERIALMANAGER_NUM_PORTS ||
passthru_port1 < 0 ||
passthru_port1 >= SERIALMANAGER_NUM_PORTS) {
passthru_port1 < 0) {
return false;
}
port1 = get_serial_by_id(passthru_port1);
port2 = get_serial_by_id(passthru_port2);
if (port1 == nullptr || port2 == nullptr) {
return false;
}
const auto *state1 = get_state_by_id(passthru_port1);
const auto *state2 = get_state_by_id(passthru_port2);
if (!state1 || !state2) {
return false;
}
port1 = hal.serial(passthru_port1);
port2 = hal.serial(passthru_port2);
baud1 = state[passthru_port1].baudrate();
baud2 = state[passthru_port2].baudrate();
baud1 = state1->baudrate();
baud2 = state2->baudrate();
timeout_s = MAX(passthru_timeout, 0);
return true;
}
Expand All @@ -725,6 +782,33 @@ void AP_SerialManager::set_protocol_and_baud(uint8_t sernum, enum SerialProtocol
}
}

#if AP_SERIALMANAGER_REGISTER_ENABLED
/*
register an external network port. It is up to the caller to use a unique id field
using AP_SERIALMANAGER_NET_PORT_1 as the base id for NET_P1_*
*/
void AP_SerialManager::register_port(RegisteredPort *port)
{
const auto idx = port->state.idx;
WITH_SEMAPHORE(port_sem);
/*
maintain the list in ID order
*/
if (registered_ports == nullptr ||
registered_ports->state.idx >= idx) {
port->next = registered_ports;
registered_ports = port;
return;
}
for (auto p = registered_ports; p; p = p->next) {
if (p->next == nullptr || p->next->state.idx >= idx) {
port->next = p->next;
p->next = port;
break;
}
}
}
#endif // AP_SERIALMANAGER_REGISTER_ENABLED

namespace AP {

Expand Down
40 changes: 38 additions & 2 deletions libraries/AP_SerialManager/AP_SerialManager.h
Expand Up @@ -115,6 +115,18 @@
#define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256
#define AP_SERIALMANAGER_MSP_BAUD 115200

#ifndef AP_SERIALMANAGER_REGISTER_ENABLED
#define AP_SERIALMANAGER_REGISTER_ENABLED HAL_ENABLE_LIBUAVCAN_DRIVERS
#endif

// serial ports registered by AP_Networking will use IDs starting at 21 for the first port
#define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_*

// serial ports registered by AP_DroneCAN will use IDs starting at 41/51 for the first port
#define AP_SERIALMANAGER_CAN_D1_PORT_1 41 // CAN_D1_UC_S1_*
#define AP_SERIALMANAGER_CAN_D2_PORT_1 51 // CAN_D2_UC_S1_*


class AP_SerialManager {
public:
AP_SerialManager();
Expand Down Expand Up @@ -205,7 +217,7 @@ class AP_SerialManager {

// get the passthru ports if enabled
bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s,
uint32_t &baud1, uint32_t &baud2) const;
uint32_t &baud1, uint32_t &baud2);

// disable passthru by settings SERIAL_PASS2 to -1
void disable_passthru(void);
Expand Down Expand Up @@ -235,12 +247,17 @@ class AP_SerialManager {
AP_SerialManager::SerialProtocol get_protocol() const {
return AP_SerialManager::SerialProtocol(protocol.get());
}
private:
AP_Int32 baud;
AP_Int16 options;
AP_Int8 protocol;

// serial index number
uint8_t idx;
};

// get a state from serial index
const UARTState *get_state_by_id(uint8_t id) const;

// search through managed serial connections looking for the
// instance-nth UART which is running protocol protocol.
// protocol_match is used to determine equivalence of one protocol
Expand All @@ -249,6 +266,25 @@ class AP_SerialManager {
const UARTState *find_protocol_instance(enum SerialProtocol protocol,
uint8_t instance) const;

#if AP_SERIALMANAGER_REGISTER_ENABLED
/*
a class for a externally registered port
used by AP_Networking
*/
class RegisteredPort : public AP_HAL::UARTDriver {
public:
RegisteredPort *next;
UARTState state;
};
RegisteredPort *registered_ports;
HAL_Semaphore port_sem;

// register an externally managed port
void register_port(RegisteredPort *port);

#endif // AP_SERIALMANAGER_REGISTER_ENABLED


private:
static AP_SerialManager *_singleton;

Expand Down