mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_SerialManager: added register_port() API
allows another library to register a UART driver for exposing via AP_SerialManager APIs
This commit is contained in:
parent
713745ed28
commit
f9f07912e6
@ -439,6 +439,8 @@ void AP_SerialManager::init()
|
|||||||
for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
|
for (uint8_t i=1; i<SERIALMANAGER_NUM_PORTS; i++) {
|
||||||
auto *uart = hal.serial(i);
|
auto *uart = hal.serial(i);
|
||||||
|
|
||||||
|
state[i].idx = i;
|
||||||
|
|
||||||
if (uart != nullptr) {
|
if (uart != nullptr) {
|
||||||
set_options(i);
|
set_options(i);
|
||||||
switch (state[i].protocol) {
|
switch (state[i].protocol) {
|
||||||
@ -589,6 +591,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
|
// if we got this far we did not find the uart
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
@ -602,10 +615,23 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
|
|||||||
if (_state == nullptr) {
|
if (_state == nullptr) {
|
||||||
return 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()
|
// set options before any user does begin()
|
||||||
AP_HAL::UARTDriver *port = hal.serial(serial_idx);
|
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) {
|
if (port) {
|
||||||
port->set_options(_state->options);
|
port->set_options(_state->options);
|
||||||
}
|
}
|
||||||
@ -637,7 +663,7 @@ int8_t AP_SerialManager::find_portnum(enum SerialProtocol protocol, uint8_t inst
|
|||||||
if (_state == nullptr) {
|
if (_state == nullptr) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
return int8_t(_state - &state[0]);
|
return int8_t(_state->idx);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_serial_by_id - gets serial by serial id
|
// get_serial_by_id - gets serial by serial id
|
||||||
@ -646,6 +672,13 @@ AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id)
|
|||||||
if (id < SERIALMANAGER_NUM_PORTS) {
|
if (id < SERIALMANAGER_NUM_PORTS) {
|
||||||
return hal.serial(id);
|
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;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -755,6 +788,17 @@ 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)
|
||||||
|
{
|
||||||
|
port->next = registered_ports;
|
||||||
|
registered_ports = port;
|
||||||
|
}
|
||||||
|
#endif // AP_SERIALMANAGER_REGISTER_ENABLED
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
|
||||||
|
@ -23,6 +23,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
|
#include <AP_Networking/AP_Networking_Config.h>
|
||||||
|
|
||||||
#ifdef HAL_UART_NUM_SERIAL_PORTS
|
#ifdef HAL_UART_NUM_SERIAL_PORTS
|
||||||
#if HAL_UART_NUM_SERIAL_PORTS >= 4
|
#if HAL_UART_NUM_SERIAL_PORTS >= 4
|
||||||
@ -150,6 +151,13 @@
|
|||||||
#define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256
|
#define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256
|
||||||
#define AP_SERIALMANAGER_MSP_BAUD 115200
|
#define AP_SERIALMANAGER_MSP_BAUD 115200
|
||||||
|
|
||||||
|
#ifndef AP_SERIALMANAGER_REGISTER_ENABLED
|
||||||
|
#define AP_SERIALMANAGER_REGISTER_ENABLED AP_NETWORKING_ENABLED
|
||||||
|
#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_*
|
||||||
|
|
||||||
class AP_SerialManager {
|
class AP_SerialManager {
|
||||||
public:
|
public:
|
||||||
AP_SerialManager();
|
AP_SerialManager();
|
||||||
@ -268,10 +276,12 @@ public:
|
|||||||
AP_SerialManager::SerialProtocol get_protocol() const {
|
AP_SerialManager::SerialProtocol get_protocol() const {
|
||||||
return AP_SerialManager::SerialProtocol(protocol.get());
|
return AP_SerialManager::SerialProtocol(protocol.get());
|
||||||
}
|
}
|
||||||
private:
|
|
||||||
AP_Int32 baud;
|
AP_Int32 baud;
|
||||||
AP_Int16 options;
|
AP_Int16 options;
|
||||||
AP_Int8 protocol;
|
AP_Int8 protocol;
|
||||||
|
|
||||||
|
// serial index number
|
||||||
|
uint8_t idx;
|
||||||
};
|
};
|
||||||
|
|
||||||
// search through managed serial connections looking for the
|
// search through managed serial connections looking for the
|
||||||
@ -282,6 +292,24 @@ public:
|
|||||||
const UARTState *find_protocol_instance(enum SerialProtocol protocol,
|
const UARTState *find_protocol_instance(enum SerialProtocol protocol,
|
||||||
uint8_t instance) const;
|
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;
|
||||||
|
|
||||||
|
// register an externally managed port
|
||||||
|
void register_port(RegisteredPort *port);
|
||||||
|
|
||||||
|
#endif // AP_SERIALMANAGER_REGISTER_ENABLED
|
||||||
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static AP_SerialManager *_singleton;
|
static AP_SerialManager *_singleton;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user