uint8_t NRF24L01_Init(uint8_t channel, uint8_t payload_size) { /* Max payload is 32bytes */ if (payload_size > 32) { payload_size = 32; } /* Fill structure */ NRF24L01_Struct.Channel = !channel; /* Set channel to some different value for NRF24L01_SetChannel() function */ NRF24L01_Struct.PayloadSize = payload_size; NRF24L01_Struct.OutPwr = NRF24L01_OutputPower_0dBm; NRF24L01_Struct.DataRate = NRF24L01_DataRate_2M; /* Reset nRF24L01+ to power on registers values */ NRF24L01_SoftwareReset(); /* Channel select */ NRF24L01_SetChannel(channel); /* Set pipeline to max possible 32 bytes */ NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P0, NRF24L01_Struct.PayloadSize); // Auto-ACK pipe NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P1, NRF24L01_Struct.PayloadSize); // Data payload pipe NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P2, NRF24L01_Struct.PayloadSize); NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P3, NRF24L01_Struct.PayloadSize); NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P4, NRF24L01_Struct.PayloadSize); NRF24L01_WriteRegister(NRF24L01_REG_RX_PW_P5, NRF24L01_Struct.PayloadSize); /* Set RF settings (2mbps, output power) */ NRF24L01_SetRF(NRF24L01_Struct.DataRate, NRF24L01_Struct.OutPwr); /* Config register */ NRF24L01_WriteRegister(NRF24L01_REG_CONFIG, NRF24L01_CONFIG); /* Enable auto-acknowledgment for all pipes */ NRF24L01_WriteRegister(NRF24L01_REG_EN_AA, 0x3F); /* Enable RX addresses */ NRF24L01_WriteRegister(NRF24L01_REG_EN_RXADDR, 0x3F); /* Auto retransmit delay: 1000 (4x250) us and Up to 15 retransmit trials */ NRF24L01_WriteRegister(NRF24L01_REG_SETUP_RETR, 0x4F); /* Dynamic length configurations: No dynamic length */ NRF24L01_WriteRegister(NRF24L01_REG_DYNPD, (0 << NRF24L01_DPL_P0) | (0 << NRF24L01_DPL_P1) | (0 << NRF24L01_DPL_P2) | (0 << NRF24L01_DPL_P3) | (0 << NRF24L01_DPL_P4) | (0 << NRF24L01_DPL_P5)); /* Clear FIFOs */ NRF24L01_FLUSH_TX(); NRF24L01_FLUSH_RX(); /* Clear interrupts */ NRF24L01_CLEAR_INTERRUPTS; /* Go to RX mode */ NRF24L01_PowerUpRx(); /* Return OK */ return 1; }
static void inavHopToNextChannel(void) { ++inavRfChannelIndex; if (inavRfChannelIndex >= inavRfChannelCount) { inavRfChannelIndex = 0; } NRF24L01_SetChannel(inavRfChannels[inavRfChannelIndex]); #ifdef DEBUG_NRF24_INAV debug[0] = inavRfChannels[inavRfChannelIndex]; #endif }
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); }
static void inavSetBound(void) { protocolState = STATE_DATA; NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN); timeOfLastHop = micros(); inavRfChannelIndex = 0; inavSetHoppingChannels(); NRF24L01_SetChannel(inavRfChannels[0]); #ifdef DEBUG_NRF24_INAV debug[0] = inavRfChannels[inavRfChannelIndex]; #endif }