AP_RCProtocol: remove intermediate srxl2 callback-chain functions

This commit is contained in:
Peter Barker 2023-04-26 23:16:32 +10:00 committed by Peter Barker
parent 294eb1db5b
commit e89ccf1fa7
2 changed files with 22 additions and 43 deletions

View File

@ -185,17 +185,8 @@ void AP_RCProtocol_SRXL2::update(void)
} }
} }
void AP_RCProtocol_SRXL2::capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t new_rssi)
{
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 != nullptr) {
srxl2->_capture_scaled_input(values_p, in_failsafe, new_rssi);
}
}
// capture SRXL2 encoded values // capture SRXL2 encoded values
void AP_RCProtocol_SRXL2::_capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t new_rssi) void AP_RCProtocol_SRXL2::capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t new_rssi)
{ {
_in_failsafe = in_failsafe; _in_failsafe = in_failsafe;
// AP rssi: -1 for unknown, 0 for no link, 255 for maximum link // AP rssi: -1 for unknown, 0 for no link, 255 for maximum link
@ -273,7 +264,7 @@ void AP_RCProtocol_SRXL2::process_handshake(uint32_t baudrate)
_handshake_start_ms = now; _handshake_start_ms = now;
// it seems the handshake protocol only sets the baudrate after receiving data // it seems the handshake protocol only sets the baudrate after receiving data
// since we are sending data unprompted make sure that the uart is set up correctly // since we are sending data unprompted make sure that the uart is set up correctly
_change_baud_rate(baudrate); change_baud_rate(baudrate);
} }
// we have not bootstrapped and attempts to listen first have failed // we have not bootstrapped and attempts to listen first have failed
@ -295,16 +286,6 @@ void AP_RCProtocol_SRXL2::process_handshake(uint32_t baudrate)
// send data to the uart // send data to the uart
void AP_RCProtocol_SRXL2::send_on_uart(uint8_t* pBuffer, uint8_t length) void AP_RCProtocol_SRXL2::send_on_uart(uint8_t* pBuffer, uint8_t length)
{
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 != nullptr) {
srxl2->_send_on_uart(pBuffer, length);
}
}
// send data to the uart
void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
{ {
AP_HAL::UARTDriver* uart = get_available_UART(); AP_HAL::UARTDriver* uart = get_available_UART();
@ -331,16 +312,6 @@ void AP_RCProtocol_SRXL2::_send_on_uart(uint8_t* pBuffer, uint8_t length)
// change the uart baud rate // change the uart baud rate
void AP_RCProtocol_SRXL2::change_baud_rate(uint32_t baudrate) void AP_RCProtocol_SRXL2::change_baud_rate(uint32_t baudrate)
{
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 != nullptr) {
srxl2->_change_baud_rate(baudrate);
}
}
// change the uart baud rate
void AP_RCProtocol_SRXL2::_change_baud_rate(uint32_t baudrate)
{ {
AP_HAL::UARTDriver* uart = get_available_UART(); AP_HAL::UARTDriver* uart = get_available_UART();
if (uart != nullptr) { if (uart != nullptr) {
@ -358,8 +329,11 @@ void AP_RCProtocol_SRXL2::_change_baud_rate(uint32_t baudrate)
// baudRate - the actual baud rate (currently either 115200 or 400000) // baudRate - the actual baud rate (currently either 115200 or 400000)
void srxlChangeBaudRate(uint8_t uart, uint32_t baudRate) void srxlChangeBaudRate(uint8_t uart, uint32_t baudRate)
{ {
AP_RCProtocol_SRXL2::change_baud_rate(baudRate); AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 != nullptr) {
srxl2->change_baud_rate(baudRate);
}
} }
// User-provided routine to actually transmit a packet on the given UART: // User-provided routine to actually transmit a packet on the given UART:
@ -368,7 +342,11 @@ void srxlChangeBaudRate(uint8_t uart, uint32_t baudRate)
// length - the number of bytes contained in pBuffer that should be sent // length - the number of bytes contained in pBuffer that should be sent
void srxlSendOnUart(uint8_t uart, uint8_t* pBuffer, uint8_t length) void srxlSendOnUart(uint8_t uart, uint8_t* pBuffer, uint8_t length)
{ {
AP_RCProtocol_SRXL2::send_on_uart(pBuffer, length); AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 != nullptr) {
srxl2->send_on_uart(pBuffer, length);
}
} }
// User-provided callback routine to fill in the telemetry data to send to the master when requested: // User-provided callback routine to fill in the telemetry data to send to the master when requested:
@ -389,10 +367,16 @@ void srxlFillTelemetry(SrxlTelemetryData* pTelemetryData)
// so be very careful to only do local operations // so be very careful to only do local operations
void srxlReceivedChannelData(SrxlChannelData* pChannelData, bool isFailsafe) void srxlReceivedChannelData(SrxlChannelData* pChannelData, bool isFailsafe)
{ {
AP_RCProtocol_SRXL2* srxl2 = AP_RCProtocol_SRXL2::get_singleton();
if (srxl2 == nullptr) {
return;
}
if (isFailsafe) { if (isFailsafe) {
AP_RCProtocol_SRXL2::capture_scaled_input((const uint8_t *)pChannelData->values, true, pChannelData->rssi); srxl2->capture_scaled_input((const uint8_t *)pChannelData->values, true, pChannelData->rssi);
} else { } else {
AP_RCProtocol_SRXL2::capture_scaled_input((const uint8_t *)srxlChData.values, false, srxlChData.rssi); srxl2->capture_scaled_input((const uint8_t *)srxlChData.values, false, srxlChData.rssi);
} }
} }

View File

@ -39,20 +39,15 @@ public:
return _singleton; return _singleton;
} }
// static functions for SRXL2 callbacks void capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t rssi);
static void capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t rssi); void send_on_uart(uint8_t* pBuffer, uint8_t length);
static void send_on_uart(uint8_t* pBuffer, uint8_t length); void change_baud_rate(uint32_t baudrate);
static void change_baud_rate(uint32_t baudrate);
// configure the VTX from Spektrum data
private: private:
static AP_RCProtocol_SRXL2* _singleton; static AP_RCProtocol_SRXL2* _singleton;
void _process_byte(uint32_t timestamp_us, uint8_t byte); void _process_byte(uint32_t timestamp_us, uint8_t byte);
void _send_on_uart(uint8_t* pBuffer, uint8_t length);
void _change_baud_rate(uint32_t baudrate);
void _capture_scaled_input(const uint8_t *values_p, bool in_failsafe, int16_t rssi);
void _bootstrap(uint8_t device_id); void _bootstrap(uint8_t device_id);
bool is_bootstrapped() const { return _device_id != 0; } bool is_bootstrapped() const { return _device_id != 0; }