1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +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

@ -374,7 +374,7 @@ static void processBinaryModeRequest(uint8_t address) {
static void flushHottRxBuffer(void)
{
while (serialTotalBytesWaiting(hottPort) > 0) {
while (serialRxBytesWaiting(hottPort) > 0) {
serialRead(hottPort);
}
}
@ -383,7 +383,7 @@ static void hottCheckSerialData(uint32_t currentMicros)
{
static bool lookingForRequest = true;
uint8_t bytesWaiting = serialTotalBytesWaiting(hottPort);
uint8_t bytesWaiting = serialRxBytesWaiting(hottPort);
if (bytesWaiting <= 1) {
return;

View file

@ -161,7 +161,7 @@ static void smartPortDataReceive(uint16_t c)
static uint8_t lastChar;
if (lastChar == FSSP_START_STOP) {
smartPortState = SPSTATE_WORKING;
if (c == FSSP_SENSOR_ID1 && (serialTotalBytesWaiting(smartPortSerialPort) == 0)) {
if (c == FSSP_SENSOR_ID1 && (serialRxBytesWaiting(smartPortSerialPort) == 0)) {
smartPortLastRequestTime = now;
smartPortHasRequest = 1;
// we only responde to these IDs
@ -283,7 +283,7 @@ void handleSmartPortTelemetry(void)
return;
}
while (serialTotalBytesWaiting(smartPortSerialPort) > 0) {
while (serialRxBytesWaiting(smartPortSerialPort) > 0) {
uint8_t c = serialRead(smartPortSerialPort);
smartPortDataReceive(c);
}