mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Added data parameter to UART RX callback
This commit is contained in:
parent
4476921cac
commit
8cb7abd15f
49 changed files with 112 additions and 67 deletions
|
@ -389,7 +389,7 @@ bool feature(uint32_t) {return false;}
|
|||
void mspSerialReleasePortIfAllocated(serialPort_t *) {}
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
|
||||
serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
void closeSerialPort(serialPort_t *) {}
|
||||
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e ) {return PORTSHARING_UNUSED;}
|
||||
failsafePhase_e failsafePhase(void) {return FAILSAFE_IDLE;}
|
||||
|
|
|
@ -212,7 +212,7 @@ void writeEEPROM() {}
|
|||
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e) {return NULL; }
|
||||
baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; }
|
||||
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; }
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) { return NULL; }
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; }
|
||||
void serialSetBaudRate(serialPort_t *, uint32_t) {}
|
||||
void serialSetMode(serialPort_t *, portMode_e) {}
|
||||
void serialPassthrough(serialPort_t *, serialPort_t *, serialConsumer *, serialConsumer *) {}
|
||||
|
|
|
@ -64,11 +64,11 @@ extern "C" {
|
|||
|
||||
serialPort_t *usbVcpOpen(void) { return NULL; }
|
||||
|
||||
serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {
|
||||
serialPort_t *uartOpen(UARTDevice_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {
|
||||
serialPort_t *openSoftSerial(softSerialPortIndex_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1381,12 +1381,11 @@ TEST(RCDeviceTest, TestDSAInfoAccessProtocol)
|
|||
}
|
||||
|
||||
extern "C" {
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
{
|
||||
UNUSED(identifier);
|
||||
UNUSED(functionMask);
|
||||
UNUSED(baudRate);
|
||||
UNUSED(callback);
|
||||
UNUSED(mode);
|
||||
UNUSED(options);
|
||||
|
||||
|
@ -1403,7 +1402,8 @@ extern "C" {
|
|||
s.txBuffer = s.txBuffer;
|
||||
|
||||
// callback works for IRQ-based RX ONLY
|
||||
s.rxCallback = NULL;
|
||||
s.rxCallback = callback;
|
||||
s.rxCallbackData = callbackData;
|
||||
s.baudRate = 0;
|
||||
|
||||
return (serialPort_t *)&s;
|
||||
|
|
|
@ -281,7 +281,7 @@ extern "C" {
|
|||
|
||||
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||
uint32_t micros(void) {return dummyTimeUs;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
|
||||
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
|
||||
serialPort_t *telemetrySharedPort = NULL;
|
||||
|
|
|
@ -111,6 +111,7 @@ serialPort_t *openSerialPort(
|
|||
serialPortIdentifier_e identifier,
|
||||
serialPortFunction_e function,
|
||||
serialReceiveCallbackPtr callback,
|
||||
void *callbackData,
|
||||
uint32_t baudrate,
|
||||
portMode_e mode,
|
||||
portOptions_e options
|
||||
|
@ -118,6 +119,7 @@ serialPort_t *openSerialPort(
|
|||
{
|
||||
openSerial_called = true;
|
||||
EXPECT_FALSE(NULL == callback);
|
||||
EXPECT_TRUE(NULL == callbackData);
|
||||
EXPECT_EQ(identifier, SERIAL_PORT_DUMMY_IDENTIFIER);
|
||||
EXPECT_EQ(options, serialExpectedOptions);
|
||||
EXPECT_EQ(function, FUNCTION_RX_SERIAL);
|
||||
|
@ -263,7 +265,7 @@ protected:
|
|||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
for (size_t i=0; i < length; i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
@ -287,7 +289,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived)
|
|||
|
||||
for (size_t i=0; i < sizeof(packet); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
|
||||
//report frame complete once
|
||||
|
@ -312,7 +314,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceivedWithBadCrc)
|
|||
isChecksumOkReturnValue = false;
|
||||
for (size_t i=0; i < sizeof(packet); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
|
||||
//no frame complete
|
||||
|
@ -338,7 +340,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap
|
|||
|
||||
for (size_t i=0; i < sizeof(packet_half); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet_half[i]);
|
||||
stub_serialRxCallback(packet_half[i], NULL);
|
||||
}
|
||||
|
||||
microseconds_stub_value += 5000;
|
||||
|
@ -346,7 +348,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap
|
|||
|
||||
for (size_t i=0; i < sizeof(packet_full); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet_full[i]);
|
||||
stub_serialRxCallback(packet_full[i], NULL);
|
||||
}
|
||||
|
||||
//report frame complete once
|
||||
|
@ -370,7 +372,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceived)
|
|||
|
||||
for (size_t i=0; i < sizeof(packet); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
|
||||
//report frame complete once
|
||||
|
@ -394,7 +396,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceivedBadCrc)
|
|||
|
||||
for (size_t i=0; i < sizeof(packet); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
|
||||
//no frame complete
|
||||
|
@ -436,7 +438,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived_not_shared_port)
|
|||
|
||||
for (size_t i=0; i < sizeof(packet); i++) {
|
||||
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn());
|
||||
stub_serialRxCallback(packet[i]);
|
||||
stub_serialRxCallback(packet[i], NULL);
|
||||
}
|
||||
|
||||
//report frame complete once
|
||||
|
|
|
@ -252,7 +252,7 @@ extern "C" {
|
|||
attitudeEulerAngles_t attitude = { { 0, 0, 0 } };
|
||||
|
||||
uint32_t micros(void) {return dummyTimeUs;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
return testBatteryVoltage;
|
||||
|
|
|
@ -300,7 +300,7 @@ uint8_t serialRead(serialPort_t *) {return 0;}
|
|||
void serialWrite(serialPort_t *, uint8_t) {}
|
||||
void serialWriteBuf(serialPort_t *, const uint8_t *, int) {}
|
||||
void serialSetMode(serialPort_t *, portMode_e) {}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||
void closeSerialPort(serialPort_t *) {}
|
||||
bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; }
|
||||
|
||||
|
|
|
@ -219,12 +219,13 @@ void serialSetMode(serialPort_t *instance, portMode_e mode)
|
|||
UNUSED(mode);
|
||||
}
|
||||
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e functionMask, serialReceiveCallbackPtr callback, void *callbackData, uint32_t baudRate, portMode_e mode, portOptions_e options)
|
||||
{
|
||||
UNUSED(identifier);
|
||||
UNUSED(functionMask);
|
||||
UNUSED(baudRate);
|
||||
UNUSED(callback);
|
||||
UNUSED(callbackData);
|
||||
UNUSED(mode);
|
||||
UNUSED(options);
|
||||
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
|
||||
extern "C" {
|
||||
#include <platform.h>
|
||||
#include "common/utils.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -140,13 +141,15 @@ serialPort_t *openSerialPort(
|
|||
serialPortIdentifier_e identifier,
|
||||
serialPortFunction_e function,
|
||||
serialReceiveCallbackPtr callback,
|
||||
void *callbackData,
|
||||
uint32_t baudrate,
|
||||
portMode_e mode,
|
||||
portOptions_e options
|
||||
)
|
||||
{
|
||||
openSerial_called = true;
|
||||
(void) callback;
|
||||
UNUSED(callback);
|
||||
UNUSED(callbackData);
|
||||
EXPECT_EQ(SERIAL_PORT_DUMMY_IDENTIFIER, identifier);
|
||||
EXPECT_EQ(SERIAL_BIDIR, options);
|
||||
EXPECT_EQ(FUNCTION_TELEMETRY_IBUS, function);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue