/* * Common setup of registers */ void NRF24L01_SetupBasic(void) { NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No auto acknowledgment 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_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes }
void NRF24L01_Init_milad(char Device_Mode, char CH, char DataRate, char *Address, char Address_Width, char Size_Payload, char Tx_Power) { //NRF24L01_CE_OUT; // Set Port DIR out // Enable Enhanced ShockBurst NRF24L01_Set_ShockBurst(_ShockBurst_OFF); NRF24L01_WriteReg(W_REGISTER | EN_AA, 0x01);//01 NRF24L01_WriteReg(W_REGISTER | SETUP_RETR, 0x13);//2f //NRF24L01_WriteReg(W_REGISTER | FEATURE, 0x02); // // RF output power in TX mode = 0dBm (Max.) // Set LNA gain NRF24L01_WriteReg(W_REGISTER | RF_SETUP, /*0b00000001 |*/ Tx_Power | DataRate);//////////// NRF24L01_Set_Address_Width(Address_Width);////////////////////// NRF24L01_Set_RX_Pipe(0, Address, Address_Width, Size_Payload); NRF24L01_Set_CH(CH); NRF24L01_Set_TX_Address(Address, Address_Width); // Set Transmit address // Bits 4..6: Reflect interrupts as active low on the IRQ pin // Bit 3: Enable CRC // Bit 2: CRC 1 Byte // Bit 1: Power Up NRF24L01_WriteReg(W_REGISTER | CONFIG, 0b00001110 | Device_Mode); delay_us(1500); }
void XN297_SetTXAddr(const u8* addr, int len) { if (len > 5) len = 5; if (len < 3) len = 3; if (is_xn297) { u8 buf[] = { 0, 0, 0, 0, 0 }; memcpy(buf, addr, len); NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5); } else { u8 buf[] = { 0x55, 0x0F, 0x71, 0x0C, 0x00 }; // bytes for XN297 preamble 0xC710F55 (28 bit) xn297_addr_len = len; if (xn297_addr_len < 4) { for (int i = 0; i < 4; ++i) { buf[i] = buf[i+1]; } } NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, buf, 5); // Receive address is complicated. We need to use scrambled actual address as a receive address // but the TX code now assumes fixed 4-byte transmit address for preamble. We need to adjust it // first. Also, if the scrambled address begings with 1 nRF24 will look for preamble byte 0xAA // instead of 0x55 to ensure enough 0-1 transitions to tune the receiver. Still need to experiment // with receiving signals. memcpy(xn297_tx_addr, addr, len); } }
static void decode_bind_packet(uint8_t *packet) { if (packet[0]==0x4b && packet[1]==0x4e && packet[2]==0x44 && packet[3]==0x5a) { txid[0] = packet[4]; txid[1] = packet[5]; txid[2] = packet[6]; txid[3] = packet[7]; txid[4] = 0x4b; kn_freq_hopping[0] = packet[8]; kn_freq_hopping[1] = packet[9]; kn_freq_hopping[2] = packet[10]; kn_freq_hopping[3] = packet[11]; if (packet[15]==0x01) { NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); } else { NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); } NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, txid, RX_TX_ADDR_LEN); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, txid, RX_TX_ADDR_LEN); bind_phase = PHASE_BOUND; rx_timeout = 1000L; // find the channel as fast as possible } }
/** Enables and configures the pipe receiving the data @param PipeNum Number of pipe @param Address Address @param AddressSize Address size @param PayloadSize Buffer size, data receiver */ void NRF24L01_Set_RX_Pipe(char PipeNum, char *Address, int AddressSize, char PayloadSize) { char Result; Result = NRF24L01_ReadReg(EN_RXADDR); NRF24L01_WriteReg(W_REGISTER | EN_RXADDR, Result | (1 << PipeNum)); NRF24L01_WriteReg(W_REGISTER | (RX_PW_P0 + PipeNum), PayloadSize); NRF24L01_WriteRegBuf(W_REGISTER | (RX_ADDR_P0 + PipeNum), Address, AddressSize); }
static int cflie_init() { NRF24L01_Initialize(); // CRC, radio on NRF24L01_SetTxRxMode(TX_EN); NRF24L01_WriteReg(NRF24L01_00_CONFIG, BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP)); NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x01); // Auto Acknowledgement for data pipe 0 NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, TX_ADDR_SIZE-2); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0x13); // 3 retransmits, 500us delay NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_channel); // Defined by model id NRF24L01_SetBitrate(data_rate); // Defined by model id NRF24L01_SetPower(Model.tx_power); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, TX_ADDR_SIZE); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, TX_ADDR_SIZE); // this sequence necessary for module from stock tx NRF24L01_ReadReg(NRF24L01_1D_FEATURE); NRF24L01_Activate(0x73); // Activate feature register NRF24L01_ReadReg(NRF24L01_1D_FEATURE); NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x01); // Enable Dynamic Payload Length on pipe 0 NRF24L01_WriteReg(NRF24L01_1D_FEATURE, 0x06); // Enable Dynamic Payload Length, enable Payload with ACK // 50ms delay in callback return 50000; }
static uint16_t esky150_init() { uint8_t rx_addr[ADDR_SIZE] = { 0x73, 0x73, 0x74, 0x63 }; uint8_t tx_addr[ADDR_SIZE] = { 0x71, 0x0A, 0x31, 0xF4 }; NRF24L01_Initialize(); NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG); NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, ADDR_SIZE-2); // 4-byte RX/TX address NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0); // Disable retransmit NRF24L01_SetPower(Model.tx_power); NRF24L01_SetBitrate(NRF24L01_BR_2M); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_addr, ADDR_SIZE); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, tx_addr, ADDR_SIZE); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, PAYLOADSIZE); // bytes of data payload for pipe 0 NRF24L01_Activate(0x73); NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 1); // Dynamic payload for data pipe 0 // Enable: Dynamic Payload Length, Payload with ACK , W_TX_PAYLOAD_NOACK NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF2401_1D_EN_DPL) | BV(NRF2401_1D_EN_ACK_PAY) | BV(NRF2401_1D_EN_DYN_ACK)); // Check for Beken BK2421/BK2423 chip // It is done by using Beken specific activate code, 0x53 // and checking that status register changed appropriately // There is no harm to run it on nRF24L01 because following // closing activate command changes state back even if it // does something on nRF24L01 NRF24L01_Activate(0x53); // magic for BK2421 bank switch printf("Trying to switch banks\n"); if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & 0x80) { printf("BK2421 detected\n"); // long nul = 0; // Beken registers don't have such nice names, so we just mention // them by their numbers // It's all magic, eavesdropped from real transfer and not even from the // data sheet - it has slightly different values NRF24L01_WriteRegisterMulti(0x00, (uint8_t *) "\x40\x4B\x01\xE2", 4); NRF24L01_WriteRegisterMulti(0x01, (uint8_t *) "\xC0\x4B\x00\x00", 4); NRF24L01_WriteRegisterMulti(0x02, (uint8_t *) "\xD0\xFC\x8C\x02", 4); NRF24L01_WriteRegisterMulti(0x03, (uint8_t *) "\xF9\x00\x39\x21", 4); NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); NRF24L01_WriteRegisterMulti(0x05, (uint8_t *) "\x24\x06\x7F\xA6", 4); NRF24L01_WriteRegisterMulti(0x0C, (uint8_t *) "\x00\x12\x73\x00", 4); NRF24L01_WriteRegisterMulti(0x0D, (uint8_t *) "\x46\xB4\x80\x00", 4); NRF24L01_WriteRegisterMulti(0x0E, (uint8_t *) "\x41\x10\x04\x82\x20\x08\x08\xF2\x7D\xEF\xFF", 11); NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC7\x96\x9A\x1B", 4); NRF24L01_WriteRegisterMulti(0x04, (uint8_t *) "\xC1\x96\x9A\x1B", 4); } else { printf("nRF24L01 detected\n"); } NRF24L01_Activate(0x53); // switch bank back // Delay 50 ms return 50000u; }
static void v202Nrf24Setup(rx_spi_protocol_e protocol) { NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowledgment NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xFF); // 4ms retransmit t/o, 15 tries if (protocol == RX_SPI_NRF24_V202_250K) { NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); } else { NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); } NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT)); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, V2X2_PAYLOAD_SIZE); // bytes of data payload for pipe 0 NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here #define RX_TX_ADDR_LEN 5 const uint8_t rx_tx_addr[RX_TX_ADDR_LEN] = {0x66, 0x88, 0x68, 0x68, 0x68}; NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, RX_TX_ADDR_LEN); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, RX_TX_ADDR_LEN); NRF24L01_FlushTx(); NRF24L01_FlushRx(); rf_ch_num = 0; bind_phase = PHASE_NOT_BOUND; prepare_to_bind(); switch_channel(); NRF24L01_SetRxMode(); // enter receive mode to start listening for packets }
void init() { NRF24L01_Initialize(); NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x02); // 4 bytes rx/tx address NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, (u8 *)"\x80\x80\x80\xB8", ADDRESS_LENGTH); // Bind address NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, (u8 *)"\x80\x80\x80\xB8", ADDRESS_LENGTH); // Bind address NRF24L01_FlushTx(); NRF24L01_FlushRx(); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, PACKET_SIZE); NRF24L01_SetPower(Model.tx_power); }
void initrx(void) { NRF24L01_Initialize(); reset_beken(); // 2-bytes CRC, radio off uint8_t config = BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PRIM_RX); NRF24L01_WriteReg(NRF24L01_00_CONFIG, config); NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknoledgement NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x03); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xFF); // 4ms retransmit t/o, 15 tries // NRF24L01_WriteReg(NRF24L01_05_RF_CH, 0x08); // Channel 8 - bind //NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetBitrate(NRF24L01_BR_250K); //250k for longer range. NRF24L01_SetPower(TXPOWER_100mW); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, V2X2_PAYLOAD_SIZE); // bytes of data payload for pipe 0 NRF24L01_WriteReg(NRF24L01_17_FIFO_STATUS, 0x00); // Just in case, no real bits to write here uint8_t rx_tx_addr[] = {0x66, 0x88, 0x68, 0x68, 0x68}; // uint8_t rx_p1_addr[] = {0x88, 0x66, 0x86, 0x86, 0x86}; NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 5); // NRF24L01_WriteRegisterMulti(NRF24L01_0B_RX_ADDR_P1, rx_p1_addr, 5); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 5); initialize_beken(); lib_timers_delaymilliseconds(50); NRF24L01_FlushTx(); NRF24L01_FlushRx(); rf_ch_num = 0; // Turn radio power on config |= BV(NRF24L01_00_PWR_UP); NRF24L01_WriteReg(NRF24L01_00_CONFIG, config); // delayMicroseconds(150); lib_timers_delaymilliseconds(1); // 6 times more than needed valid_packets = missed_packets = bad_packets = 0; if (usersettings.boundprotocol == PROTO_NONE) { bind_phase = PHASE_NOT_BOUND; prepare_to_bind(); } else { // Prepare to listen to bound protocol, if fails // try to bind bind_phase = PHASE_JUST_BOUND; set_bound(); } switch_channel(); }
static void update_telemetry() { static u8 frameloss = 0; // Read and reset count of dropped packets frameloss += NRF24L01_ReadReg(NRF24L01_08_OBSERVE_TX) >> 4; NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_channel); // reset packet loss counter Telemetry.value[TELEM_DSM_FLOG_FRAMELOSS] = frameloss; TELEMETRY_SetUpdated(TELEM_DSM_FLOG_FRAMELOSS); if (packet_ack() == PKT_ACKED) { // See if the ACK packet is a cflie log packet // A log data packet is a minimum of 5 bytes. Ignore anything less. if (rx_payload_len >= 5) { // Port 5 = log, Channel 2 = data if (rx_packet[0] == crtp_create_header(CRTP_PORT_LOG, CRTP_LOG_CHAN_LOGDATA)) { // The log block ID if (rx_packet[1] == CFLIE_TELEM_LOG_BLOCK_ID) { // Bytes 6 and 7 are the Vbat in mV units u16 vBat; memcpy(&vBat, &rx_packet[5], sizeof(u16)); Telemetry.value[TELEM_DSM_FLOG_VOLT2] = (s32) (vBat / 10); // The log value expects tenths of volts TELEMETRY_SetUpdated(TELEM_DSM_FLOG_VOLT2); // Bytes 8 and 9 are the ExtVbat in mV units u16 extVBat; memcpy(&extVBat, &rx_packet[7], sizeof(u16)); Telemetry.value[TELEM_DSM_FLOG_VOLT1] = (s32) (extVBat / 10); // The log value expects tenths of volts TELEMETRY_SetUpdated(TELEM_DSM_FLOG_VOLT1); } } } } }
void send_packet() { u32 temp; for(u8 ch=0;ch<8;ch++) { temp=((s32)Channels[ch] * 0x1f1 / CHAN_MAX_VALUE + 0x5d9)<<3; packet[2*ch]=temp>>8; packet[2*ch+1]=temp; } for(u8 i=0; i<ADDRESS_LENGTH; i++) packet[16+i]=packet[23-i]; NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_FlushTx(); NRF24L01_WritePayload(packet, PACKET_SIZE); // Check and adjust transmission power. We do this after // transmission to not bother with timeout after power // settings change - we have plenty of time until next // packet. if (tx_power != Model.tx_power) { //Keep transmit power updated tx_power = Model.tx_power; NRF24L01_SetPower(tx_power); } }
const void *CFlie_Cmds(enum ProtoCmds cmd) { // dbgprintf("CFlie_Cmds %d\n", cmd); switch(cmd) { case PROTOCMD_INIT: initialize(); return 0; case PROTOCMD_DEINIT: CLOCK_StopTimer(); NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0); return 0; case PROTOCMD_CHECK_AUTOBIND: return (void *)0L; // never Autobind // always Autobind case PROTOCMD_BIND: initialize(); return 0; case PROTOCMD_NUMCHAN: switch(Model.proto_opts[PROTOOPTS_CRTP_MODE]) { case CRTP_MODE_CPPM: return (void *)12L; // A, E, R, T, up to 8 additional aux channels case CRTP_MODE_RPYT: default: return (void *)5L; // A, E, R, T, + or x mode } case PROTOCMD_DEFAULT_NUMCHAN: return (void *)5L; case PROTOCMD_CURRENT_ID: return Model.fixed_id ? (void *)((unsigned long)Model.fixed_id) : 0; case PROTOCMD_GETOPTIONS: return cflie_opts; case PROTOCMD_TELEMETRYSTATE: return (void *)(long)(Model.proto_opts[PROTOOPTS_TELEMETRY] == TELEM_OFF ? PROTO_TELEM_OFF : PROTO_TELEM_ON); case PROTOCMD_TELEMETRYTYPE: return (void *)(long) TELEM_DSM; default: break; } return 0; }
static void set_bind_address() { NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, 0x01); // 3-byte RX/TX address for bind packets u8 rx_tx_addr[] = {0x00, 0x00, 0x00}; NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rx_tx_addr, 3); NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rx_tx_addr, 3); }
static void esky_init2() { NRF24L01_FlushTx(); packet_sent = 0; rf_ch_num = 0; u32 channel_ord = rand32_r(0, 0) % 74; channel_code = 10 + (u8) channel_ord; u8 channel1, channel2; channel1 = 10 + (u8) ((37 + channel_ord*5) % 74); channel2 = 10 + (u8) ((channel_ord*5) % 74) ; printf("channel code %d, channel1 %d, channel2 %d\n", (int) channel_code, (int) channel1, (int) channel2); rf_channels[0] = channel1; rf_channels[1] = channel1; rf_channels[2] = channel1; rf_channels[3] = channel2; rf_channels[4] = channel2; rf_channels[5] = channel2; end_bytes[0] = 6; end_bytes[1] = channel1*2; end_bytes[2] = channel2*2; end_bytes[3] = 6; end_bytes[4] = channel1*2; end_bytes[5] = channel2*2; // Turn radio power on NRF24L01_SetTxRxMode(TX_EN); u8 config = BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO) | BV(NRF24L01_00_PWR_UP); NRF24L01_WriteReg(NRF24L01_00_CONFIG, config); // Implicit delay in callback // delayMicroseconds(150); }
//Send a packet and receive the ACK //Return true in case of success. //Polling implementation unsigned char NRF24L01_SendPacket(char *payload, char len, char *ackPayload, char *ackLen) { char status = 0; //Send the packet NRF24L01_TxPacket(payload, len); //Wait for something to happen while(((status=NRF24L01_Nop())&0x70) == 0); // Clear the flags NRF24L01_WriteReg(REG_STATUS, 0x70); //Return FALSE if the packet has not been transmited if (status&BIT_MAX_RT) { NRF24L01_FlushTx(); return 0; } //Receive the ackPayload if any has been received if (status&BIT_RX_DR) *ackLen = NRF24L01_RxPacket(ackPayload); else *ackLen = 0; NRF24L01_FlushRx(); return status&BIT_TX_DS; }
static void send_search_packet() { uint8_t buf[1]; buf[0] = 0xff; // clear packet status bits and TX FIFO NRF24L01_WriteReg(NRF24L01_07_STATUS, (BV(NRF24L01_07_TX_DS) | BV(NRF24L01_07_MAX_RT))); NRF24L01_FlushTx(); if (rf_channel++ > 125) { rf_channel = 0; switch(data_rate) { case NRF24L01_BR_250K: data_rate = NRF24L01_BR_1M; break; case NRF24L01_BR_1M: data_rate = NRF24L01_BR_2M; break; case NRF24L01_BR_2M: data_rate = NRF24L01_BR_250K; break; } } set_rate_channel(data_rate, rf_channel); NRF24L01_WritePayload(buf, sizeof(buf)); ++packet_counter; }
// Update telemetry using the ACK packet payload static void update_telemetry_ackpkt() { static u8 frameloss = 0; // Read and reset count of dropped packets frameloss += NRF24L01_ReadReg(NRF24L01_08_OBSERVE_TX) >> 4; NRF24L01_WriteReg(NRF24L01_05_RF_CH, rf_channel); // reset packet loss counter Telemetry.value[TELEM_DSM_FLOG_FRAMELOSS] = frameloss; TELEMETRY_SetUpdated(TELEM_DSM_FLOG_FRAMELOSS); if (packet_ack() == PKT_ACKED) { // Make sure this is an ACK packet (first byte will alternate between 0xF3 and 0xF7 if (rx_packet[0] == 0xF3 || rx_packet[0] == 0xF7) { // If ACK packet contains RSSI (proper length and byte 1 is 0x01) if(rx_payload_len >= 3 && rx_packet[1] == 0x01) { Telemetry.value[TELEM_CFLIE_RSSI] = rx_packet[2]; TELEMETRY_SetUpdated(TELEM_CFLIE_RSSI); } // If ACK packet contains VBAT (proper length and byte 3 is 0x02) if(rx_payload_len >= 8 && rx_packet[3] == 0x02) { u32 vBat = 0; memcpy(&vBat, &rx_packet[4], sizeof(u32)); Telemetry.value[TELEM_CFLIE_INTERNAL_VBAT] = (s32)(vBat / 10); // The log value expects centivolts TELEMETRY_SetUpdated(TELEM_CFLIE_INTERNAL_VBAT); } } } }
uintptr_t CFlie_Cmds(enum ProtoCmds cmd) { // dbgprintf("CFlie_Cmds %d\n", cmd); switch(cmd) { case PROTOCMD_INIT: initialize(); return 0; case PROTOCMD_DEINIT: CLOCK_StopTimer(); NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0); return 0; case PROTOCMD_CHECK_AUTOBIND: return 0; // never Autobind case PROTOCMD_BIND: initialize(); return 0; case PROTOCMD_NUMCHAN: switch(Model.proto_opts[PROTOOPTS_CRTP_MODE]) { case CRTP_MODE_CPPM: return 12; // A, E, R, T, up to 8 additional aux channels case CRTP_MODE_RPYT: default: return 5; // A, E, R, T, + or x mode } case PROTOCMD_DEFAULT_NUMCHAN: return 5; case PROTOCMD_CURRENT_ID: return Model.fixed_id; case PROTOCMD_GETOPTIONS: return (uintptr_t)cflie_opts; case PROTOCMD_TELEMETRYSTATE: return (Model.proto_opts[PROTOOPTS_TELEMETRY] == TELEM_OFF ? PROTO_TELEM_OFF : PROTO_TELEM_ON); case PROTOCMD_TELEMETRYTYPE: return TELEM_DSM; case PROTOCMD_CHANNELMAP: return AETRG; default: break; } return 0; }
void XN297_Configure(u8 flags) { if (!is_xn297) { xn297_crc = !!(flags & BV(NRF24L01_00_EN_CRC)); flags &= ~(BV(NRF24L01_00_EN_CRC) | BV(NRF24L01_00_CRCO)); } NRF24L01_WriteReg(NRF24L01_00_CONFIG, flags); }
void NRF24L01_SetTxRxMode(enum TXRX_State mode) { if(mode == TX_EN) { CE_lo(); NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s) | (1 << NRF24L01_07_TX_DS) | (1 << NRF24L01_07_MAX_RT)); NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC) // switch to TX mode | (1 << NRF24L01_00_CRCO) | (1 << NRF24L01_00_PWR_UP)); usleep(130); CE_hi(); } else if (mode == RX_EN) { CE_lo(); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // reset the flag(s) NRF24L01_WriteReg(NRF24L01_00_CONFIG, 0x0F); // switch to RX mode NRF24L01_WriteReg(NRF24L01_07_STATUS, (1 << NRF24L01_07_RX_DR) //reset the flag(s) | (1 << NRF24L01_07_TX_DS) | (1 << NRF24L01_07_MAX_RT)); NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC) // switch to RX mode | (1 << NRF24L01_00_CRCO) | (1 << NRF24L01_00_PWR_UP) | (1 << NRF24L01_00_PRIM_RX)); usleep(130); CE_hi(); } else { NRF24L01_WriteReg(NRF24L01_00_CONFIG, (1 << NRF24L01_00_EN_CRC)); //PowerDown CE_lo(); } }
void XN297_SetRXAddr(const u8* addr, int len) { if (len > 5) len = 5; if (len < 3) len = 3; u8 buf[] = { 0, 0, 0, 0, 0 }; memcpy(buf, addr, len); if (is_xn297) { NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5); } else { memcpy(xn297_rx_addr, addr, len); for (int i = 0; i < xn297_addr_len; ++i) { buf[i] = xn297_rx_addr[i] ^ xn297_scramble[xn297_addr_len-i-1]; } NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, len-2); NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, buf, 5); } }
static void DM002_init() { NRF24L01_Initialize(); NRF24L01_SetTxRxMode(TX_EN); XN297_SetTXAddr((uint8_t *)"\x26\xA8\x67\x35\xCC", DM002_ADDRESS_SIZE); NRF24L01_FlushTx(); NRF24L01_FlushRx(); NRF24L01_WriteReg(NRF24L01_07_STATUS, 0x70); // Clear data ready, data sent, and retransmit NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No Auto Acknowldgement on all data pipes NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, 0x01); // Enable data pipe 0 only NRF24L01_SetBitrate(NRF24L01_BR_1M); // 1Mbps NRF24L01_SetPower(Model.tx_power); // Check for Beken BK2421/BK2423 chip // It is done by using Beken specific activate code, 0x53 // and checking that status register changed appropriately // There is no harm to run it on nRF24L01 because following // closing activate command changes state back even if it // does something on nRF24L01 NRF24L01_Activate(0x53); // magic for BK2421 bank switch dbgprintf("Trying to switch banks\n"); if (NRF24L01_ReadReg(NRF24L01_07_STATUS) & 0x80) { dbgprintf("BK2421 detected\n"); // Beken registers don't have such nice names, so we just mention // them by their numbers // It's all magic, eavesdropped from real transfer and not even from the // data sheet - it has slightly different values NRF24L01_WriteRegisterMulti(0x00, (u8 *) "\x40\x4B\x01\xE2", 4); NRF24L01_WriteRegisterMulti(0x01, (u8 *) "\xC0\x4B\x00\x00", 4); NRF24L01_WriteRegisterMulti(0x02, (u8 *) "\xD0\xFC\x8C\x02", 4); NRF24L01_WriteRegisterMulti(0x03, (u8 *) "\x99\x00\x39\x21", 4); NRF24L01_WriteRegisterMulti(0x04, (u8 *) "\xD9\x96\x82\x1B", 4); NRF24L01_WriteRegisterMulti(0x05, (u8 *) "\x24\x06\x7F\xA6", 4); NRF24L01_WriteRegisterMulti(0x0C, (u8 *) "\x00\x12\x73\x00", 4); NRF24L01_WriteRegisterMulti(0x0D, (u8 *) "\x46\xB4\x80\x00", 4); NRF24L01_WriteRegisterMulti(0x04, (u8 *) "\xDF\x96\x82\x1B", 4); NRF24L01_WriteRegisterMulti(0x04, (u8 *) "\xD9\x96\x82\x1B", 4); } else { dbgprintf("nRF24L01 detected\n"); } NRF24L01_Activate(0x53); // switch bank back }
/* * Enter receive mode */ void NRF24L01_SetRxMode(void) { NRF24_CE_LO(); // drop into standby mode // set the PRIM_RX bit NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BV(NRF24L01_00_CONFIG_PRIM_RX)); NRF24L01_ClearAllInterrupts(); // finally set CE high to start enter RX mode NRF24_CE_HI(); // nRF24L01+ will now transition from Standby mode to RX mode after 130 microseconds settling time }
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); }
u8 NRF24L01_SetBitrate(u8 bitrate) { // Note that bitrate 250kbps (and bit RF_DR_LOW) is valid only // for nRF24L01+. There is no way to programmatically tell it from // older version, nRF24L01, but the older is practically phased out // by Nordic, so we assume that we deal with with modern version. // Bit 0 goes to RF_DR_HIGH, bit 1 - to RF_DR_LOW rf_setup = (rf_setup & 0xD7) | ((bitrate & 0x02) << 4) | ((bitrate & 0x01) << 3); return NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, rf_setup); }
void NRF24L01_UpdateRfSetup() { unsigned char setup=0; setup = setupDataRate[radioConf.dataRate]; setup |= radioConf.power<<1; if (radioConf.contCarrier) setup |= 0x90; NRF24L01_WriteReg(REG_RF_SETUP, setup); }
static uint16_t esky150_init2() { NRF24L01_FlushTx(); NRF24L01_FlushRx(); packet_sent = 0; packet_count = 0; rf_ch_num = 0; // Turn radio power on NRF24L01_WriteReg(NRF24L01_00_CONFIG, CRC_CONFIG | BV(NRF24L01_00_PWR_UP)); // delayMicroseconds(150); return 150u; }
//Set the radio channel. void NRF24L01_SetChannel(char channel) { //Test the input if(channel<0 || channel>125) return; //Change the channel RADIO_DIS_CE(); NRF24L01_WriteReg(REG_RF_CH, channel); //CE is continously activated if in continous carrier mode if(radioConf.contCarrier) RADIO_EN_CE(); }
//Raw registers update (for internal use) void NRF24L01_UpdateRetr() { char ard=0; unsigned char nbytes; if (radioConf.ard & ARD_PLOAD) { nbytes = ((radioConf.ard&0x7F)>32)?32:(radioConf.ard&0x7F); for (ard=0; ardStep[radioConf.dataRate][ard]<nbytes; ard++) continue; } else ard = radioConf.ard & 0x0F; NRF24L01_WriteReg(REG_SETUP_RETR, (ard<<4) | (radioConf.arc&0x0F)); }