1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Merge branch 'master' into betaflight

Conflicts:
	src/main/blackbox/blackbox_io.c
	src/main/drivers/serial_usb_vcp.c
	src/main/flight/imu.c
	src/main/mw.c
	src/main/target/CC3D/target.h
This commit is contained in:
borisbstyle 2015-10-12 23:53:43 +02:00
commit 4b3ba927e9
50 changed files with 544 additions and 250 deletions

View file

@ -403,7 +403,7 @@ void onSerialRxPinChange(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
}
}
uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
uint8_t softSerialRxBytesWaiting(serialPort_t *instance)
{
if ((instance->mode & MODE_RX) == 0) {
return 0;
@ -414,6 +414,19 @@ uint8_t softSerialTotalBytesWaiting(serialPort_t *instance)
return (s->port.rxBufferHead - s->port.rxBufferTail) & (s->port.rxBufferSize - 1);
}
uint8_t softSerialTxBytesFree(serialPort_t *instance)
{
if ((instance->mode & MODE_TX) == 0) {
return 0;
}
softSerial_t *s = (softSerial_t *)instance;
uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
return (s->port.txBufferSize - 1) - bytesUsed;
}
uint8_t softSerialReadByte(serialPort_t *instance)
{
uint8_t ch;
@ -422,7 +435,7 @@ uint8_t softSerialReadByte(serialPort_t *instance)
return 0;
}
if (softSerialTotalBytesWaiting(instance) == 0) {
if (softSerialRxBytesWaiting(instance) == 0) {
return 0;
}
@ -460,7 +473,8 @@ bool isSoftSerialTransmitBufferEmpty(serialPort_t *instance)
const struct serialPortVTable softSerialVTable[] = {
{
softSerialWriteByte,
softSerialTotalBytesWaiting,
softSerialRxBytesWaiting,
softSerialTxBytesFree,
softSerialReadByte,
softSerialSetBaudRate,
isSoftSerialTransmitBufferEmpty,