Skip to content

Commit

Permalink
Merge pull request betaflight#11536 from SteveCEvans/frsky_range
Browse files Browse the repository at this point in the history
Frsky range check issues
  • Loading branch information
blckmn committed Apr 22, 2022
2 parents eb31068 + 8bc7548 commit 3119648
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 25 deletions.
12 changes: 4 additions & 8 deletions src/main/drivers/rx/rx_cc2500.c
Expand Up @@ -50,20 +50,12 @@ void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)

void cc2500WriteCommand(uint8_t command, uint8_t data)
{
// Burst writes require an interbyte gap, see fig. 7, pg. 22 in https://www.ti.com/lit/ds/symlink/cc2500.pdf
// As such gaps can't be inserted if DMA is being used, inhibit DMA on this bus for the duration of this call
rxSpiDmaEnable(false);
rxSpiWriteCommand(command, data);
rxSpiDmaEnable(true);
}

void cc2500WriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
{
// Burst writes require an interbyte gap, see fig. 7, pg. 22 in https://www.ti.com/lit/ds/symlink/cc2500.pdf
// As such gaps can't be inserted if DMA is being used, inhibit DMA on this bus for the duration of this call
rxSpiDmaEnable(false);
rxSpiWriteCommandMulti(command, data, length);
rxSpiDmaEnable(true);
}

void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len)
Expand Down Expand Up @@ -116,6 +108,10 @@ void cc2500SetPower(uint8_t power)

uint8_t cc2500Reset(void)
{
// Writes require an interbyte gap, see fig. 7, pg. 22 in https://www.ti.com/lit/ds/symlink/cc2500.pdf
// As such gaps can't be inserted if DMA is being used, inhibit DMA for this device
rxSpiDmaEnable(false);

cc2500Strobe(CC2500_SRES);
delayMicroseconds(1000); // 1000us
// CC2500_SetTxRxMode(TXRX_OFF);
Expand Down
8 changes: 0 additions & 8 deletions src/main/fc/core.c
Expand Up @@ -1262,14 +1262,6 @@ FAST_CODE bool pidLoopReady(void)
return false;
}

FAST_CODE bool rxFrameReady(void)
{
if ((activePidLoopDenom == 1) || (pidUpdateCounter % activePidLoopDenom == 0)) {
return true;
}
return false;
}

FAST_CODE void taskFiltering(timeUs_t currentTimeUs)
{
gyroFiltering(currentTimeUs);
Expand Down
1 change: 0 additions & 1 deletion src/main/fc/core.h
Expand Up @@ -82,7 +82,6 @@ void updateArmingStatus(void);
void taskGyroSample(timeUs_t currentTimeUs);
bool gyroFilterReady(void);
bool pidLoopReady(void);
bool rxFrameReady(void);
void taskFiltering(timeUs_t currentTimeUs);
void taskMainPidLoop(timeUs_t currentTimeUs);

Expand Down
2 changes: 2 additions & 0 deletions src/main/rx/cc2500_frsky_shared.c
Expand Up @@ -435,6 +435,8 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
protocolState = STATE_STARTING;

break;

case STATE_STARTING:
default:
ret = handlePacket(packet, &protocolState);

Expand Down
14 changes: 7 additions & 7 deletions src/main/scheduler/scheduler.c
Expand Up @@ -503,13 +503,13 @@ FAST_CODE void scheduler(void)
if (pidLoopReady()) {
taskExecutionTimeUs += schedulerExecuteTask(getTask(TASK_PID), currentTimeUs);
}
if (rxFrameReady()) {
// Check for incoming RX data. Don't do this in the checker as that is called repeatedly within
// a given gyro loop, and ELRS takes a long time to process this and so can only be safely processed
// before the checkers
rxFrameCheck(currentTimeUs, cmpTimeUs(currentTimeUs, getTask(TASK_RX)->lastExecutedAtUs));
}
// Check for failsafe conditions every 10ms, independently of the Rx Task, which runs at 33hz.

// Check for incoming RX data. Don't do this in the checker as that is called repeatedly within
// a given gyro loop, and ELRS takes a long time to process this and so can only be safely processed
// before the checkers
rxFrameCheck(currentTimeUs, cmpTimeUs(currentTimeUs, getTask(TASK_RX)->lastExecutedAtUs));

// Check for failsafe conditions without reliance on the RX task being well behaved
if (cmp32(millis(), lastFailsafeCheckMs) > PERIOD_RXDATA_FAILURE) {
// This is very low cost taking less that 4us every 10ms
failsafeCheckDataFailurePeriod();
Expand Down
1 change: 0 additions & 1 deletion src/test/unit/scheduler_unittest.cc
Expand Up @@ -67,7 +67,6 @@ extern "C" {
int16_t debug[1];
uint8_t debugMode = 0;

bool rxFrameReady(void) { return 0; }
void rxFrameCheck(timeUs_t, timeDelta_t) {}

// set up micros() to simulate time
Expand Down

0 comments on commit 3119648

Please sign in to comment.