APM:Libraries
RC_NRF_parser.h
Go to the documentation of this file.
1 #pragma once
2 
3 /*
4  imported from Betaflight/INAV
5 
6 */
7 
8 
9 #ifdef BOARD_NRF_CS_PIN
10 
11 /*#pragma GCC push_options
12 #pragma GCC optimize ("O2")
13 #pragma GCC pop_options
14 */
15 #include <AP_HAL/AP_HAL.h>
16 
17 
18 #include "AP_HAL_F4Light.h"
19 
20 #include "RC_parser.h"
21 
22 #define USE_WHITENING
23 #define USE_AUTO_ACKKNOWLEDGEMENT
24 
25  enum { // instead of #define
26  RX_TX_ADDR_LEN=5,
27  NRF_MAX_PAYLOAD_SIZE=32,
28  BIND_PAYLOAD_SIZE = 16,
29  BIND_PAYLOAD0 = 0xad, // 10101101
30  BIND_PAYLOAD1 = 0xc9, // 11001001
31  BIND_ACK_PAYLOAD0 = 0x95, // 10010101
32  BIND_ACK_PAYLOAD1 = 0xa9, // 10101001
33  TELEMETRY_ACK_PAYLOAD0= 0x5a, // 01011010
34  // TELEMETRY_ACK_PAYLOAD1 is sequence count
35  DATA_PAYLOAD0 = 0x00,
36  DATA_PAYLOAD1 = 0x00,
37  INAV_PROTOCOL_PAYLOAD_SIZE_MIN = 8,
38  INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT = 16,
39  INAV_PROTOCOL_PAYLOAD_SIZE_MAX = 18,
40  RX_TX_ADDR_4 = 0xD2, // rxTxAddr[4] always set to this value
41 
42  INAV_RF_CHANNEL_COUNT_MAX = 8,
43  INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT = 4,
44  INAV_RF_BIND_CHANNEL = 0x4c,
45 
46  };
47 
48 
49 // RC channels in AETR order
50 typedef enum {
51  RC_SPI_ROLL = 0,
52  RC_SPI_PITCH,
53  RC_SPI_THROTTLE,
54  RC_SPI_YAW,
55  RC_SPI_AUX1,
56  RC_SPI_AUX2,
57  RC_SPI_AUX3,
58  RC_SPI_AUX4,
59  RC_SPI_AUX5,
60  RC_SPI_AUX6,
61  RC_SPI_AUX7,
62  RC_SPI_AUX8,
63  RC_SPI_AUX9,
64  RC_SPI_AUX10,
65  RC_SPI_AUX11,
66  RC_SPI_AUX12,
67  RC_SPI_AUX13,
68  RC_SPI_AUX14
69 } rc_spi_aetr_e;
70 
71 enum {
72  RATE_LOW = 0,
73  RATE_MID = 1,
74  RATE_HIGH = 2,
75 };
76 
77 enum {
78  FLAG_FLIP = 0x01,
79  FLAG_PICTURE = 0x02,
80  FLAG_VIDEO = 0x04,
81  FLAG_RTH = 0x08,
82  FLAG_HEADLESS = 0x10,
83 };
84 
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))
88 
89 class F4Light::NRF_parser : public F4Light::_parser {
90 public:
91  NRF_parser() {}
92 
93 
94  typedef enum {
95  RX_SPI_RECEIVED_NONE = 0,
96  RX_SPI_RECEIVED_BIND,
97  RX_SPI_RECEIVED_DATA
98  } rx_spi_received_e;
99 
100  typedef enum {
101  STATE_BIND = 0,
102  STATE_DATA
103  } protocol_state_t;
104 
105 
106  void init(uint8_t ch);
107 
108 private:
110 
111  void set_val(uint8_t ch, uint16_t val);
112 
113  uint32_t *fixedIdPtr; // TODO parameter
114 
115  void cs_assert(){ nrf->set_speed(AP_HAL::Device::SPEED_HIGH); GPIO::_write(BOARD_NRF_CS_PIN, 0); }
116  void cs_release(){ GPIO::_write(BOARD_NRF_CS_PIN, 1); }
117 
118 // high level functions
119 
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);
130 
131 
132 // low level
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);
141 
142 
143  static rx_spi_received_e state;
144  static protocol_state_t protocolState;
145  static uint8_t rxTxAddr[RX_TX_ADDR_LEN];
146 
147 // Utility functions
148 
149  void NRF24L01_FlushTx(void);
150  void NRF24L01_FlushRx(void);
151  uint8_t NRF24L01_Activate(uint8_t code);
152 
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);
160 };
161 
162 #endif // BOARD_NRF_CS_PIN
163 
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
virtual void init(uint8_t ch)=0
static int state
Definition: Util.cpp:20
virtual bool set_speed(Device::Speed speed) override=0