APM:Libraries
driver_cc2500.cpp
Go to the documentation of this file.
1 /*
2  low level driver for the TI CC2500 radio on SPI
3 
4  With thanks to betaflight
5 */
6 
7 #include "driver_cc2500.h"
8 #include <utility>
9 
10 // #pragma GCC optimize("O0")
11 
12 extern const AP_HAL::HAL& hal;
13 
14 // constructor
16  dev(std::move(_dev))
17 {}
18 
19 void Radio_CC2500::ReadFifo(uint8_t *dpbuffer, uint8_t len)
20 {
21  (void)dev->read_registers(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
22 }
23 
24 void Radio_CC2500::WriteFifo(const uint8_t *dpbuffer, uint8_t len)
25 {
27 }
28 
29 void Radio_CC2500::ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
30 {
31  (void)dev->read_registers(address, data, length);
32 }
33 
34 void Radio_CC2500::WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length)
35 {
36  uint8_t buf[length+1];
37  buf[0] = address;
38  memcpy(&buf[1], data, length);
39  dev->transfer(buf, length+1, nullptr, 0);
40 }
41 
42 uint8_t Radio_CC2500::ReadReg(uint8_t reg)
43 {
44  uint8_t ret = 0;
45  (void)dev->read_registers(reg | CC2500_READ_SINGLE, &ret, 1);
46  return ret;
47 }
48 
49 uint8_t Radio_CC2500::Strobe(uint8_t address)
50 {
51  uint8_t status=0;
52  (void)dev->transfer(&address, 1, &status, 1);
53  return status;
54 }
55 
56 void Radio_CC2500::WriteReg(uint8_t address, uint8_t data)
57 {
58  (void)dev->write_register(address, data);
59 }
60 
61 void Radio_CC2500::SetPower(uint8_t power)
62 {
63  const uint8_t patable[8] = {
64  0xC5, // -12dbm
65  0x97, // -10dbm
66  0x6E, // -8dbm
67  0x7F, // -6dbm
68  0xA9, // -4dbm
69  0xBB, // -2dbm
70  0xFE, // 0dbm
71  0xFF // 1.5dbm
72  };
73  if (power > 7) {
74  power = 7;
75  }
76  WriteReg(CC2500_3E_PATABLE, patable[power]);
77 }
78 
80 {
82  hal.scheduler->delay_microseconds(1000);
83  // CC2500_SetTxRxMode(TXRX_OFF);
84  // RX_EN_off;//off tx
85  // TX_EN_off;//off rx
86  return ReadReg(CC2500_0E_FREQ1) == 0xC4; // check if reset
87 }
88 
89 /*
90  write register with up to 5 retries
91  */
92 void Radio_CC2500::WriteRegCheck(uint8_t address, uint8_t data)
93 {
94  uint8_t tries=5;
95  while (--tries) {
96  dev->write_register(address, data);
97  uint8_t v = ReadReg(address);
98  if (v == data) break;
99  }
100 }
uint8_t ReadReg(uint8_t reg)
bool Reset(void)
void ReadFifo(uint8_t *dpbuffer, uint8_t len)
#define CC2500_WRITE_BURST
Definition: driver_cc2500.h:82
void WriteFifo(const uint8_t *dpbuffer, uint8_t len)
void WriteReg(uint8_t address, uint8_t data)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length)
void ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
float v
Definition: Printf.cpp:15
#define CC2500_READ_BURST
Definition: driver_cc2500.h:84
#define CC2500_READ_SINGLE
Definition: driver_cc2500.h:83
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
void SetPower(uint8_t power)
virtual void delay_microseconds(uint16_t us)=0
void WriteRegCheck(uint8_t address, uint8_t data)
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
Radio_CC2500(AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev)
#define CC2500_SRES
Definition: driver_cc2500.h:87
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint8_t Strobe(uint8_t address)