9 #ifdef BOARD_NRF_CS_PIN 23 #define USE_AUTO_ACKKNOWLEDGEMENT 27 NRF_MAX_PAYLOAD_SIZE=32,
28 BIND_PAYLOAD_SIZE = 16,
31 BIND_ACK_PAYLOAD0 = 0x95,
32 BIND_ACK_PAYLOAD1 = 0xa9,
33 TELEMETRY_ACK_PAYLOAD0= 0x5a,
37 INAV_PROTOCOL_PAYLOAD_SIZE_MIN = 8,
38 INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT = 16,
39 INAV_PROTOCOL_PAYLOAD_SIZE_MAX = 18,
42 INAV_RF_CHANNEL_COUNT_MAX = 8,
43 INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT = 4,
44 INAV_RF_BIND_CHANNEL = 0x4c,
85 #define PWM_RANGE_MIN 1100 86 #define PWM_RANGE_MAX 1900 87 #define PWM_RANGE_MIDDLE (PWM_RANGE_MIN + ((PWM_RANGE_MAX - PWM_RANGE_MIN) / 2)) 95 RX_SPI_RECEIVED_NONE = 0,
106 void init(uint8_t ch);
111 void set_val(uint8_t ch, uint16_t val);
113 uint32_t *fixedIdPtr;
120 void inavNrf24Setup(
const uint32_t *fixedId);
121 void inavNrf24SetRcDataFromPayload(uint16_t *rcData,
const uint8_t *payload);
122 void inavSetHoppingChannels(
void);
123 void inavHopToNextChannel(
void);
124 void writeBindAckPayload(uint8_t *payload);
125 void writeTelemetryAckPayload(
void);
126 void writeAckPayload(uint8_t *data, uint8_t length);
127 void inavSetBound(
void);
128 void whitenPayload(uint8_t *payload, uint8_t len);
129 bool checkBindPacket(
const uint8_t *payload);
133 void NRF24L01_Initialize(uint8_t baseConfig);
134 uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data);
135 uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg,
const uint8_t *data, uint8_t length);
136 uint8_t NRF24L01_WritePayload(
const uint8_t *data, uint8_t length);
137 uint8_t NRF24L01_WriteAckPayload(
const uint8_t *data, uint8_t length, uint8_t pipe);
138 uint8_t NRF24L01_ReadReg(uint8_t reg);
139 uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
140 uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
143 static rx_spi_received_e
state;
144 static protocol_state_t protocolState;
145 static uint8_t rxTxAddr[RX_TX_ADDR_LEN];
149 void NRF24L01_FlushTx(
void);
150 void NRF24L01_FlushRx(
void);
151 uint8_t NRF24L01_Activate(uint8_t code);
153 void NRF24L01_SetupBasic(
void);
154 void NRF24L01_SetStandbyMode(
void);
155 void NRF24L01_SetRxMode(
void);
156 void NRF24L01_SetTxMode(
void);
157 void NRF24L01_ClearAllInterrupts(
void);
158 void NRF24L01_SetChannel(uint8_t channel);
159 bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length);
162 #endif // BOARD_NRF_CS_PIN
static void _write(uint8_t pin, uint8_t value)
virtual void init(uint8_t ch)=0
virtual bool set_speed(Device::Speed speed) override=0