driver_cc2500.cpp 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105
  1. /*
  2. low level driver for the TI CC2500 radio on SPI
  3. With thanks to betaflight
  4. */
  5. #include "driver_cc2500.h"
  6. #include <utility>
  7. #pragma GCC optimize("O0")
  8. extern const AP_HAL::HAL& hal;
  9. // constructor
  10. Radio_CC2500::Radio_CC2500(AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev) :
  11. dev(std::move(_dev))
  12. {}
  13. void Radio_CC2500::ReadFifo(uint8_t *dpbuffer, uint8_t len)
  14. {
  15. (void)dev->read_registers(CC2500_3F_RXFIFO | CC2500_READ_BURST, dpbuffer, len);
  16. }
  17. void Radio_CC2500::WriteFifo(const uint8_t *dpbuffer, uint8_t len)
  18. {
  19. WriteRegisterMulti(CC2500_3F_TXFIFO | CC2500_WRITE_BURST, dpbuffer, len);
  20. }
  21. void Radio_CC2500::ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
  22. {
  23. (void)dev->read_registers(address, data, length);
  24. }
  25. void Radio_CC2500::WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t length)
  26. {
  27. uint8_t buf[length+1];
  28. buf[0] = address;
  29. memcpy(&buf[1], data, length);
  30. dev->transfer(buf, length+1, nullptr, 0);
  31. }
  32. uint8_t Radio_CC2500::ReadReg(uint8_t reg)
  33. {
  34. uint8_t ret = 0;
  35. (void)dev->read_registers(reg | CC2500_READ_SINGLE, &ret, 1);
  36. return ret;
  37. }
  38. uint8_t Radio_CC2500::Strobe(uint8_t address)
  39. {
  40. uint8_t status=0;
  41. (void)dev->transfer(&address, 1, &status, 1);
  42. return status;
  43. }
  44. void Radio_CC2500::WriteReg(uint8_t address, uint8_t data)
  45. {
  46. (void)dev->write_register(address, data);
  47. }
  48. void Radio_CC2500::SetPower(uint8_t power)
  49. {
  50. const uint8_t patable[8] = {
  51. 0xC6, // -12dbm
  52. 0x97, // -10dbm
  53. 0x6E, // -8dbm
  54. 0x7F, // -6dbm
  55. 0xA9, // -4dbm
  56. 0xBB, // -2dbm
  57. 0xFE, // 0dbm
  58. 0xFF // 1.5dbm
  59. };
  60. if (power > 7) {
  61. power = 7;
  62. }
  63. if (power != last_power) {
  64. WriteReg(CC2500_3E_PATABLE, patable[power]);
  65. last_power = power;
  66. }
  67. }
  68. bool Radio_CC2500::Reset(void)
  69. {
  70. Strobe(CC2500_SRES);
  71. hal.scheduler->delay_microseconds(1000);
  72. // CC2500_SetTxRxMode(TXRX_OFF);
  73. // RX_EN_off;//off tx
  74. // TX_EN_off;//off rx
  75. return ReadReg(CC2500_0E_FREQ1) == 0xC4; // check if reset
  76. }
  77. /*
  78. write register with up to 5 retries
  79. */
  80. void Radio_CC2500::WriteRegCheck(uint8_t address, uint8_t data)
  81. {
  82. uint8_t tries=5;
  83. while (--tries) {
  84. dev->write_register(address, data);
  85. uint8_t v = ReadReg(address);
  86. if (v == data) {
  87. break;
  88. }
  89. }
  90. }