23 #if defined(BOARD_NRF_CS_PIN) && defined(BOARD_NRF_NAME) 26 static uint8_t NRF_Buffer[NRF_MAX_PAYLOAD_SIZE];
27 static uint8_t ackPayload[NRF24L01_MAX_PAYLOAD_SIZE];
29 NRF_parser::uint8_t rxTxAddr[RX_TX_ADDR_LEN] = {0x4b,0x5c,0x6d,0x7e,0x8f};
31 static const uint8_t inavRfChannelHoppingCount = INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT;
32 static uint8_t inavRfChannelCount;
33 static uint8_t inavRfChannelIndex;
34 static uint8_t inavRfChannels[INAV_RF_CHANNEL_COUNT_MAX];
38 memset((
void *)&val[0], 0,
sizeof(val));
53 void NRF_parser::_timer() {
56 switch (protocolState) {
58 if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
59 whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
60 const bool bindPacket = checkBindPacket(NRF_Buffer);
62 state = RX_SPI_RECEIVED_BIND;
63 writeBindAckPayload(NRF_Buffer);
73 if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
74 whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
75 receivedPowerSnapshot = NRF24L01_ReadReg(NRF24L01_09_RPD);
76 const bool bindPacket = checkBindPacket(NRF_Buffer);
79 state = RX_SPI_RECEIVED_BIND;
80 writeBindAckPayload(NRF_Buffer);
82 state = RX_SPI_RECEIVED_DATA;
83 writeTelemetryAckPayload();
86 if ((
state == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
87 inavHopToNextChannel();
88 timeOfLastHop = timeNowUs;
96 bool NRF_parser::checkBindPacket(
const uint8_t *payload)
98 bool bindPacket =
false;
99 if (payload[0] == BIND_PAYLOAD0 && payload[1] == BIND_PAYLOAD1) {
101 if (protocolState ==STATE_BIND) {
102 rxTxAddr[0] = payload[2];
103 rxTxAddr[1] = payload[3];
104 rxTxAddr[2] = payload[4];
105 rxTxAddr[3] = payload[5];
106 rxTxAddr[4] = payload[6];
111 if (fixedIdPtr !=
NULL && *fixedIdPtr == 0) {
113 memcpy(fixedIdPtr, rxTxAddr,
sizeof(uint32_t));
121 void NRF_parser::whitenPayload(uint8_t *payload, uint8_t len)
124 uint8_t whitenCoeff = 0x6b;
126 for (uint8_t m = 1; m; m <<= 1) {
127 if (whitenCoeff & 0x80) {
141 void NRF_parser::inavSetBound(
void)
143 protocolState = STATE_DATA;
144 NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
145 NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
148 inavRfChannelIndex = 0;
149 inavSetHoppingChannels();
150 NRF24L01_SetChannel(inavRfChannels[0]);
151 #ifdef DEBUG_NRF24_INAV 152 debug[0] = inavRfChannels[inavRfChannelIndex];
156 void NRF_parser::writeAckPayload(uint8_t *data, uint8_t length)
158 whitenPayload(data, length);
159 NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_MAX_RT));
160 NRF24L01_WriteAckPayload(data, length, NRF24L01_PIPE0);
163 void NRF_parser::writeTelemetryAckPayload(
void)
165 #ifdef TELEMETRY_NRF24_LTM 167 static uint8_t sequenceNumber = 0;
168 static ltm_frame_e ltmFrameType = LTM_FRAME_START;
170 ackPayload[0] = TELEMETRY_ACK_PAYLOAD0;
171 ackPayload[1] = sequenceNumber++;
172 const int ackPayloadSize = getLtmFrame(&ackPayload[2], ltmFrameType) + 2;
175 if (ltmFrameType > LTM_FRAME_COUNT) {
176 ltmFrameType = LTM_FRAME_START;
178 writeAckPayload(ackPayload, ackPayloadSize);
179 #ifdef DEBUG_NRF24_INAV 180 debug[1] = ackPayload[1];
181 debug[2] = ackPayload[2];
182 debug[3] = ackPayload[3];
188 void NRF_parser::writeBindAckPayload(uint8_t *payload)
190 #ifdef USE_AUTO_ACKKNOWLEDGEMENT 191 memcpy(ackPayload, payload, BIND_PAYLOAD_SIZE);
193 ackPayload[0] = BIND_ACK_PAYLOAD0;
194 ackPayload[1] = BIND_ACK_PAYLOAD1;
196 ackPayload[7] = inavRfChannelHoppingCount;
198 switch (payloadSize) {
199 case INAV_PROTOCOL_PAYLOAD_SIZE_MIN:
200 case INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT:
201 case INAV_PROTOCOL_PAYLOAD_SIZE_MAX:
202 ackPayload[8] = payloadSize;
205 ackPayload[8] = INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT;
208 writeAckPayload(ackPayload, BIND_PAYLOAD_SIZE);
215 void NRF_parser::inavHopToNextChannel(
void)
217 ++inavRfChannelIndex;
218 if (inavRfChannelIndex >= inavRfChannelCount) {
219 inavRfChannelIndex = 0;
221 NRF24L01_SetChannel(inavRfChannels[inavRfChannelIndex]);
222 #ifdef DEBUG_NRF24_INAV 223 debug[0] = inavRfChannels[inavRfChannelIndex];
228 void NRF_parser::inavSetHoppingChannels(
void)
230 #ifdef NO_RF_CHANNEL_HOPPING 232 inavRfChannelCount = 1;
233 inavRfChannels[0] = INAV_RF_BIND_CHANNEL;
235 inavRfChannelCount = inavRfChannelHoppingCount;
236 const uint8_t addr = rxTxAddr[0];
237 uint8_t ch = 0x10 + (addr & 0x07);
238 for (
int ii = 0; ii < INAV_RF_CHANNEL_COUNT_MAX; ++ii) {
239 inavRfChannels[ii] = ch;
245 void NRF_parser::set_val(uint8_t ch, uint16_t val){
246 if(_val[ch] != val) {
253 void NRF_parser::inavNrf24SetRcDataFromPayload(uint16_t *rcData,
const uint8_t *payload)
255 memset(_val, 0,
sizeof(_val));
258 uint8_t lowBits = payload[6];
259 set_val(RC_SPI_ROLL, PWM_RANGE_MIN + ((payload[2] << 2) | (lowBits & 0x03)) );
261 set_val(RC_SPI_PITCH, PWM_RANGE_MIN + ((payload[3] << 2) | (lowBits & 0x03)) );
263 set_val(RC_SPI_THROTTLE, PWM_RANGE_MIN + ((payload[4] << 2) | (lowBits & 0x03)) );
265 set_val(RC_SPI_YAW, PWM_RANGE_MIN + ((payload[5] << 2) | (lowBits & 0x03)) );
267 if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MIN) {
269 set_val(RC_SPI_AUX1, PWM_RANGE_MIN + (payload[7] << 2) );
270 set_val(RC_SPI_AUX2, PWM_RANGE_MIN + (payload[1] << 2) );
271 _channels = RC_SPI_AUX2+1;
274 const uint8_t rate = payload[7];
276 if (rate == RATE_HIGH) {
277 set_val(RC_CHANNEL_RATE, PWM_RANGE_MAX);
278 }
else if (rate == RATE_MID) {
279 set_val(RC_CHANNEL_RATE, PWM_RANGE_MIDDLE);
281 set_val(RC_CHANNEL_RATE, PWM_RANGE_MIN);
285 const uint8_t flags = payload[8];
286 set_val(RC_CHANNEL_FLIP, (flags & FLAG_FLIP) ? PWM_RANGE_MAX : PWM_RANGE_MIN );
287 set_val(RC_CHANNEL_PICTURE, (flags & FLAG_PICTURE) ? PWM_RANGE_MAX : PWM_RANGE_MIN );
288 set_val(RC_CHANNEL_VIDEO, (flags & FLAG_VIDEO) ? PWM_RANGE_MAX : PWM_RANGE_MIN );
289 set_val(RC_CHANNEL_HEADLESS, (flags & FLAG_HEADLESS) ? PWM_RANGE_MAX : PWM_RANGE_MIN );
290 set_val(RC_CHANNEL_RTH, (flags & FLAG_RTH) ? PWM_RANGE_MAX : PWM_RANGE_MIN );
293 lowBits = payload[13];
294 set_val(RC_SPI_AUX7, PWM_RANGE_MIN + ((payload[9] << 2) | (lowBits & 0x03)) );
296 set_val(RC_SPI_AUX8, PWM_RANGE_MIN + ((payload[10] << 2) | (lowBits & 0x03)) );
298 set_val(RC_SPI_AUX9, PWM_RANGE_MIN + ((payload[11] << 2) | (lowBits & 0x03)) );
300 set_val(RC_SPI_AUX10, PWM_RANGE_MIN + ((payload[12] << 2) | (lowBits & 0x03)) );
304 set_val(RC_SPI_AUX11, PWM_RANGE_MIN + (payload[14] << 2) );
305 set_val(RC_SPI_AUX12, PWM_RANGE_MIN + (payload[15] << 2) );
307 _channels = RC_SPI_AUX12+1;
309 if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MAX) {
312 set_val(RC_SPI_AUX13, PWM_RANGE_MIN + (payload[16] << 2) );
313 set_val(RC_SPI_AUX14, PWM_RANGE_MIN + (payload[17] << 2) );
314 _channels = RC_SPI_AUX14+1;
320 void NRF_parser::inavNrf24Setup(
const uint32_t *fixedId)
324 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));
326 #ifdef USE_AUTO_ACKKNOWLEDGEMENT 327 NRF24L01_WriteReg(NRF24L01_01_EN_AA, BV(NRF24L01_01_EN_AA_ENAA_P0));
328 NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
329 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES);
330 NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0);
331 NRF24L01_Activate(0x73);
332 NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BV(NRF24L01_1D_FEATURE_EN_DPL));
333 NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BV(NRF24L01_1C_DYNPD_DPL_P0));
336 NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
338 NRF24L01_SetupBasic();
341 NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
343 NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
344 NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize);
346 #ifdef USE_BIND_ADDRESS_FOR_DATA_STATE 351 if (fixedId ==
NULL || *fixedId == 0) {
353 protocolState = STATE_BIND;
354 inavRfChannelCount = 1;
355 inavRfChannelIndex = 0;
356 NRF24L01_SetChannel(INAV_RF_BIND_CHANNEL);
358 fixedIdPtr = (uint32_t*)fixedId;
360 memcpy(rxTxAddr, fixedId,
sizeof(uint32_t));
361 rxTxAddr[4] = RX_TX_ADDR_4;
366 NRF24L01_SetRxMode();
368 writeAckPayload(ackPayload, payloadSize);
376 #define NRF24_CE_HI() cs_assert() 377 #define NRF24_CE_LO() cs_release() 382 #define R_REGISTER 0x00 383 #define W_REGISTER 0x20 384 #define REGISTER_MASK 0x1F 385 #define ACTIVATE 0x50 386 #define R_RX_PL_WID 0x60 387 #define R_RX_PAYLOAD 0x61 388 #define W_TX_PAYLOAD 0xA0 389 #define W_ACK_PAYLOAD 0xA8 390 #define FLUSH_TX 0xE1 391 #define FLUSH_RX 0xE2 392 #define REUSE_TX_PL 0xE3 395 uint8_t rxSpiTransferByte(uint8_t data){
398 nrf->transfer(&data,1,&bt,1);
402 uint8_t rxSpiWriteByte(uint8_t data)
405 const uint8_t ret = rxSpiTransferByte(data);
410 void rxSpiWriteCommand(uint8_t reg, uint8_t data){
411 uint8_t bt[2] = {reg, data };
413 nrf->transfer(&bt,2,
NULL,0);
417 void rxSpiWriteCommandMulti(uint8_t reg,
const uint8_t *data, uint8_t length){
418 uint8_t bt[length+1];
420 for(uint8_t i=0;i<length;i++) {
423 nrf->transfer(&bt,length,
NULL,0);
426 void rxSpiReadCommand(uint8_t reg, uint8_t bt){
428 return nrf->transfer(bt);
432 bool rxSpiReadCommandMulti(uint8_t reg, uint8_t op, uint8_t *data, uint8_t length)
433 const uint8_t ret = rxSpiTransferByte(reg);
434 for (uint8_t i = 0; i < length; i++) {
435 data[i] = rxSpiTransferByte(op);
441 void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
443 rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
446 void NRF24L01_WriteRegisterMulti(uint8_t reg,
const uint8_t *data, uint8_t length)
448 rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
456 uint8_t NRF24L01_WritePayload(
const uint8_t *data, uint8_t length)
458 return rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
461 uint8_t NRF24L01_WriteAckPayload(
const uint8_t *data, uint8_t length, uint8_t pipe)
463 return rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
466 uint8_t NRF24L01_ReadReg(uint8_t reg)
468 return rxSpiReadCommand(R_REGISTER | (REGISTER_MASK & reg), NOP);
471 uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
473 return rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
479 uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
481 return rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
489 void NRF24L01_FlushTx()
491 rxSpiWriteByte(FLUSH_TX);
497 void NRF24L01_FlushRx()
499 rxSpiWriteByte(FLUSH_RX);
502 uint8_t NRF24L01_Activate(uint8_t code)
504 return rxSpiWriteCommand(ACTIVATE, code);
508 static uint8_t standbyConfig;
510 void NRF24L01_Initialize(uint8_t baseConfig)
512 standbyConfig = BV(NRF24L01_00_CONFIG_PWR_UP) | baseConfig;
515 static const timeUs_t settlingTimeUs = 100000;
516 const timeUs_t currentTimeUs =
micros();
517 if (currentTimeUs < settlingTimeUs) {
521 NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig);
530 void NRF24L01_SetupBasic(
void)
532 NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00);
533 NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
534 NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES);
535 NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00);
542 void NRF24L01_SetStandbyMode(
void)
546 NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig);
552 void NRF24L01_SetRxMode(
void)
556 NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BV(NRF24L01_00_CONFIG_PRIM_RX));
557 NRF24L01_ClearAllInterrupts();
566 void NRF24L01_SetTxMode(
void)
569 NRF24L01_SetStandbyMode();
570 NRF24L01_ClearAllInterrupts();
579 void NRF24L01_ClearAllInterrupts(
void)
582 NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT));
586 bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length)
588 if (NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_RX_EMPTY)) {
591 NRF24L01_ReadPayload(data, length);
597 #endif // BOARD_NRF24_CS_PIN
static void _pinMode(uint8_t pin, uint8_t output)
static void delayMicroseconds(uint16_t us)
Simple circular buffer for PEM input.
static void _write(uint8_t pin, uint8_t value)
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define debug(fmt, args ...)
virtual OwnPtr< SPIDevice > get_device(const char *name)
AP_HAL::SPIDeviceManager * spi
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void init()
Generic board initialization function.
#define FUNCTOR_BIND_MEMBER(func, rettype,...)