APM:Libraries
AP_Radio_cc2500.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  AP_Radio implementation for CC2500 2.4GHz radio.
19 
20  With thanks to cleanflight and betaflight projects
21  */
22 
23 #include "AP_Radio_backend.h"
24 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
25 #include "hal.h"
26 #include "telem_structure.h"
27 #include "driver_cc2500.h"
28 
29 #define CC2500_MAX_CHANNELS 16
30 
32 {
33 public:
35 
36  // init - initialise radio
37  bool init(void) override;
38 
39  // rest radio
40  bool reset(void) override;
41 
42  // send a packet
43  bool send(const uint8_t *pkt, uint16_t len) override;
44 
45  // start bind process as a receiver
46  void start_recv_bind(void) override;
47 
48  // return time in microseconds of last received R/C packet
49  uint32_t last_recv_us(void) override;
50 
51  // return number of input channels
52  uint8_t num_channels(void) override;
53 
54  // return current PWM of a channel
55  uint16_t read(uint8_t chan) override;
56 
57  // handle a data96 mavlink packet for fw upload
58  void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override;
59 
60  // update status
61  void update(void) override;
62 
63  // get TX fw version
64  uint32_t get_tx_version(void) override {
65  // pack date into 16 bits for vendor_id in AUTOPILOT_VERSION
66  return (uint16_t(tx_date.firmware_year)<<12) + (uint16_t(tx_date.firmware_month)<<8) + tx_date.firmware_day;
67  }
68 
69  // get radio statistics structure
70  const AP_Radio::stats &get_stats(void) override;
71 
72  // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
73  void set_wifi_channel(uint8_t channel) {
74  // t_status.wifi_chan = channel;
75  }
76 
77 private:
80  static thread_t *_irq_handler_ctx;
81  static virtual_timer_t timeout_vt;
82 
83  static void irq_handler_thd(void* arg);
84  static void trigger_irq_radio_event(void);
85  static void trigger_timeout_event(void *arg);
86 
87  void radio_init(void);
88 
89  // semaphore between ISR and main thread
91 
94 
96 
98 
99  uint8_t calData[255][3];
100  uint8_t bindTxId[2];
101  int8_t bindOffset;
102  uint8_t bindHopData[47];
103  uint8_t rxNum;
104  uint8_t listLength;
105  uint8_t channr;
106  uint8_t chanskip;
107  int8_t fcc_chan;
108  uint32_t packet_timer;
109  static uint32_t irq_time_us;
110  const uint32_t sync_time_us = 9000;
111  uint8_t chan_count;
112  uint32_t lost;
113  uint32_t timeouts;
115  uint8_t packet3;
118  uint64_t bind_mask;
119  uint8_t best_lqi;
121 
122  uint32_t timeTunedMs;
123 
124  void initTuneRx(void);
125  void initialiseData(uint8_t adr);
126  void initGetBind(void);
127  bool tuneRx(uint8_t ccLen, uint8_t *packet);
128  bool getBindData(uint8_t ccLen, uint8_t *packet);
129  bool check_best_LQI(void);
130  void setChannel(uint8_t channel);
131  void nextChannel(uint8_t skip);
132 
133  void parse_frSkyX(const uint8_t *packet);
134  uint16_t calc_crc(const uint8_t *data, uint8_t len);
135  bool check_crc(uint8_t ccLen, uint8_t *packet);
136 
137  void send_D16_telemetry(void);
138  void send_SRT_telemetry(void);
139 
140  void irq_handler(void);
141  void irq_timeout(void);
142 
143  // bind structure saved to storage
144  static const uint16_t bind_magic = 0x120a;
145  struct PACKED bind_info {
146  uint16_t magic;
147  uint8_t bindTxId[2];
148  int8_t bindOffset;
149  uint8_t listLength;
150  uint8_t bindHopData[47];
151  };
152 
153  void save_bind_info(void);
154  bool load_bind_info(void);
155 
156  enum {
168  } protocolState;
169 
170  struct config {
171  uint8_t reg;
172  uint8_t value;
173  };
174  static const config radio_config[];
175 
176  struct {
177  mavlink_channel_t chan;
178  bool need_ack;
179  uint8_t counter;
180  uint8_t sequence;
181  uint32_t offset;
182  uint32_t length;
183  uint32_t acked;
184  uint8_t len;
186  uint8_t pending_data[92];
187  } fwupload;
188 
189  struct {
190  uint8_t firmware_year;
191  uint8_t firmware_month;
192  uint8_t firmware_day;
193  } tx_date;
194 
196  uint32_t last_pps_ms;
197  uint8_t tx_rssi;
198  uint8_t tx_pps;
199 
200  bool handle_D16_packet(const uint8_t *packet);
201  bool handle_SRT_packet(const uint8_t *packet);
202 
203  // check sending of fw upload ack
204  void check_fw_ack(void);
205 };
206 
207 
208 #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
209 
mavlink_channel_t chan
void nextChannel(uint8_t skip)
static thread_t * _irq_handler_ctx
bool send(const uint8_t *pkt, uint16_t len) override
static void trigger_timeout_event(void *arg)
AP_Radio_cc2500(AP_Radio &radio)
Radio_CC2500 cc2500
uint16_t pwm_channels[CC2500_MAX_CHANNELS]
bool tuneRx(uint8_t ccLen, uint8_t *packet)
bool init(void) override
void update(void) override
void save_bind_info(void)
bool getBindData(uint8_t ccLen, uint8_t *packet)
void irq_timeout(void)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
AP_Radio::stats last_stats
void radio_init(void)
enum telem_type fw_type
uint16_t read(uint8_t chan) override
void send_D16_telemetry(void)
void setChannel(uint8_t channel)
struct telem_status t_status
enum AP_Radio_cc2500::@167 protocolState
void start_recv_bind(void) override
static uint32_t irq_time_us
uint32_t last_recv_us(void) override
struct AP_Radio_cc2500::@169 tx_date
bool reset(void) override
void check_fw_ack(void)
uint8_t num_channels(void) override
#define CC2500_MAX_CHANNELS
uint8_t calData[255][3]
uint8_t pending_data[92]
void initTuneRx(void)
const uint32_t sync_time_us
void initialiseData(uint8_t adr)
bool handle_D16_packet(const uint8_t *packet)
void irq_handler(void)
bool check_crc(uint8_t ccLen, uint8_t *packet)
static virtual_timer_t timeout_vt
static void trigger_irq_radio_event(void)
telem_type
AP_Radio::stats stats
void parse_frSkyX(const uint8_t *packet)
static AP_Radio_cc2500 * radio_instance
uint8_t bindHopData[47]
bool handle_SRT_packet(const uint8_t *packet)
void send_SRT_telemetry(void)
bool check_best_LQI(void)
void set_wifi_channel(uint8_t channel)
uint8_t bindTxId[2]
#define PACKED
Definition: AP_Common.h:28
AP_HAL::Semaphore * sem
struct AP_Radio_cc2500::@168 fwupload
const AP_Radio::stats & get_stats(void) override
void initGetBind(void)
uint16_t calc_crc(const uint8_t *data, uint8_t len)
static const config radio_config[]
bool load_bind_info(void)
uint32_t get_tx_version(void) override
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override
static void irq_handler_thd(void *arg)
static const uint16_t bind_magic