AP_SerialManager: remove set_console_baud, factor out find_protocol_instance

This commit is contained in:
Peter Barker 2018-04-18 16:13:02 +10:00 committed by Peter Barker
parent 7a3eb69818
commit 37145253d9
2 changed files with 25 additions and 40 deletions

View File

@ -276,10 +276,8 @@ void AP_SerialManager::init()
}
}
// find_serial - searches available serial ports for the first instance that allows the given protocol
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns uart on success, nullptr if a serial port cannot be found
AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, uint8_t instance) const
const AP_SerialManager::UARTState *AP_SerialManager::find_protocol_instance(enum SerialProtocol protocol, uint8_t instance) const
{
uint8_t found_instance = 0;
@ -287,7 +285,7 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
if (found_instance == instance) {
return state[i].uart;
return &state[i];
}
found_instance++;
}
@ -297,25 +295,28 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol,
return nullptr;
}
// find_serial - searches available serial ports for the first instance that allows the given protocol
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns uart on success, nullptr if a serial port cannot be found
AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, uint8_t instance) const
{
const struct UARTState *_state = find_protocol_instance(protocol, instance);
if (_state == nullptr) {
return nullptr;
}
return _state->uart;
}
// find_baudrate - searches available serial ports for the first instance that allows the given protocol
// instance should be zero if searching for the first instance, 1 for the second, etc
// returns baudrate on success, 0 if a serial port cannot be found
uint32_t AP_SerialManager::find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
{
uint8_t found_instance = 0;
// search for matching protocol
for(uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
if (found_instance == instance) {
return map_baudrate(state[i].baud);
}
found_instance++;
}
const struct UARTState *_state = find_protocol_instance(protocol, instance);
if (_state == nullptr) {
return 0;
}
// if we got this far we did not find the uart
return 0;
return _state->baud;
}
// get_mavlink_channel - provides the mavlink channel associated with a given protocol
@ -364,24 +365,6 @@ void AP_SerialManager::set_blocking_writes_all(bool blocking)
}
}
// set_console_baud - sets the console's baud rate to the rate specified by the protocol
void AP_SerialManager::set_console_baud(enum SerialProtocol protocol, uint8_t instance) const
{
uint8_t found_instance = 0;
// find baud rate of this protocol
for (uint8_t i=0; i<SERIALMANAGER_NUM_PORTS; i++) {
if (protocol_match(protocol, (enum SerialProtocol)state[i].protocol.get())) {
if (instance == found_instance) {
// set console's baud rate
state[0].uart->begin(map_baudrate(state[i].baud));
return;
}
found_instance++;
}
}
}
/*
* map from a 16 bit EEPROM baud rate to a real baud rate.
* For PX4 we can do 1.5MBit, although 921600 is more reliable.

View File

@ -136,9 +136,6 @@ public:
// set_blocking_writes_all - sets block_writes on or off for all serial channels
void set_blocking_writes_all(bool blocking);
// set_console_baud - sets the console's baud rate to the rate specified by the protocol
void set_console_baud(enum SerialProtocol protocol, uint8_t instance) const;
// parameter var table
static const struct AP_Param::GroupInfo var_info[];
@ -146,12 +143,17 @@ private:
static AP_SerialManager *_instance;
// array of uart info
struct {
struct UARTState {
AP_Int8 protocol;
AP_Int32 baud;
AP_HAL::UARTDriver* uart;
} state[SERIALMANAGER_NUM_PORTS];
// search through managed serial connections looking for the
// instance-nth UART which is running protocol protocol
const UARTState *find_protocol_instance(enum SerialProtocol protocol,
uint8_t instance) const;
uint32_t map_baudrate(int32_t rate) const;
// protocol_match - returns true if the protocols match