static void inavNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId, int rfChannelHoppingCount) { UNUSED(protocol); UNUSED(rfChannelHoppingCount); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC, only get IRQ pin interrupt on RX_DR NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO) | BV(NRF24L01_00_CONFIG_MASK_MAX_RT) | BV(NRF24L01_00_CONFIG_MASK_TX_DS)); #ifdef USE_AUTO_ACKKNOWLEDGEMENT NRF24L01_WriteReg(NRF24L01_01_EN_AA, BV(NRF24L01_01_EN_AA_ENAA_P0)); // auto acknowledgment on P0 NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); NRF24L01_Activate(0x73); // activate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BV(NRF24L01_1D_FEATURE_EN_DPL)); NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BV(NRF24L01_1C_DYNPD_DPL_P0)); // enable dynamic payload length on P0 //NRF24L01_Activate(0x73); // deactivate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN); #else NRF24L01_SetupBasic(); #endif NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); // RX_ADDR for pipes P1-P5 are left at default values NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN); NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize); #ifdef USE_BIND_ADDRESS_FOR_DATA_STATE inavSetBound(); UNUSED(rxSpiId); #else rxSpiId = NULL; // !!TODO remove this once configurator supports setting rx_id if (rxSpiId == NULL || *rxSpiId == 0) { rxSpiIdPtr = NULL; protocolState = STATE_BIND; inavRfChannelCount = 1; inavRfChannelIndex = 0; NRF24L01_SetChannel(INAV_RF_BIND_CHANNEL); } else { rxSpiIdPtr = (uint32_t*)rxSpiId; // use the rxTxAddr provided and go straight into DATA_STATE memcpy(rxTxAddr, rxSpiId, sizeof(uint32_t)); rxTxAddr[4] = RX_TX_ADDR_4; inavSetBound(); } #endif NRF24L01_SetRxMode(); // enter receive mode to start listening for packets // put a null packet in the transmit buffer to be sent as ACK on first receive writeAckPayload(ackPayload, payloadSize); }
/* * This is called periodically by the scheduler. * Returns RX_SPI_RECEIVED_DATA if a data packet was received. */ rx_spi_received_e inavNrf24DataReceived(uint8_t *payload) { rx_spi_received_e ret = RX_SPI_RECEIVED_NONE; timeUs_t timeNowUs; switch (protocolState) { case STATE_BIND: if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) { whitenPayload(payload, payloadSize); const bool bindPacket = inavCheckBindPacket(payload); if (bindPacket) { ret = RX_SPI_RECEIVED_BIND; writeBindAckPayload(payload); // got a bind packet, so set the hopping channels and the rxTxAddr and start listening for data inavSetBound(); } } break; case STATE_DATA: timeNowUs = micros(); // read the payload, processing of payload is deferred if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) { whitenPayload(payload, payloadSize); receivedPowerSnapshot = NRF24L01_ReadReg(NRF24L01_09_RPD); // set to 1 if received power > -64dBm const bool bindPacket = inavCheckBindPacket(payload); if (bindPacket) { // transmitter may still continue to transmit bind packets after we have switched to data mode ret = RX_SPI_RECEIVED_BIND; writeBindAckPayload(payload); } else { ret = RX_SPI_RECEIVED_DATA; writeTelemetryAckPayload(); } } if ((ret == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) { inavHopToNextChannel(); timeOfLastHop = timeNowUs; } break; } return ret; }