AP_RAMTRON.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127
  1. /*
  2. driver for RAMTRON FRAM persistent memory devices. These are used
  3. for parameter and waypoint storage on most FMUv1, FMUv2, FMUv3 and FMUv4
  4. boards
  5. */
  6. #include "AP_RAMTRON.h"
  7. extern const AP_HAL::HAL &hal;
  8. // register numbers
  9. #define RAMTRON_RDID 0x9f
  10. #define RAMTRON_READ 0x03
  11. #define RAMTRON_RDSR 0x05
  12. #define RAMTRON_WREN 0x06
  13. #define RAMTRON_WRITE 0x02
  14. /*
  15. list of supported devices. Thanks to NuttX ramtron driver
  16. */
  17. const AP_RAMTRON::ramtron_id AP_RAMTRON::ramtron_ids[] = {
  18. { 0x21, 0x00, 16, 2}, // FM25V01
  19. { 0x21, 0x08, 16, 2}, // FM25V01A
  20. { 0x22, 0x00, 32, 2}, // FM25V02
  21. { 0x22, 0x08, 32, 2}, // FM25V02A
  22. { 0x22, 0x01, 32, 2}, // FM25VN02
  23. { 0x23, 0x00, 64, 2}, // FM25V05
  24. { 0x23, 0x01, 64, 2}, // FM25VN05
  25. { 0x24, 0x00, 128, 3}, // FM25V10
  26. { 0x24, 0x01, 128, 3}, // FM25VN10
  27. { 0x25, 0x08, 256, 3}, // FM25V20A
  28. { 0x26, 0x08, 512, 3}, // CY15B104Q
  29. { 0x27, 0x03, 128, 3}, // MB85RS1MT
  30. { 0x05, 0x09, 32, 3}, // B85RS256B
  31. };
  32. // initialise the driver
  33. bool AP_RAMTRON::init(void)
  34. {
  35. dev = hal.spi->get_device("ramtron");
  36. if (!dev) {
  37. return false;
  38. }
  39. WITH_SEMAPHORE(dev->get_semaphore());
  40. struct rdid {
  41. uint8_t manufacturer[6];
  42. uint8_t memory;
  43. uint8_t id1;
  44. uint8_t id2;
  45. } rdid;
  46. if (!dev->read_registers(RAMTRON_RDID, (uint8_t *)&rdid, sizeof(rdid))) {
  47. return false;
  48. }
  49. for (uint8_t i=0; i<ARRAY_SIZE(ramtron_ids); i++) {
  50. if (ramtron_ids[i].id1 == rdid.id1 &&
  51. ramtron_ids[i].id2 == rdid.id2) {
  52. id = i;
  53. return true;
  54. }
  55. }
  56. hal.console->printf("Unknown RAMTRON manufacturer=%02x memory=%02x id1=%02x id2=%02x\n",
  57. rdid.manufacturer[0], rdid.memory, rdid.id1, rdid.id2);
  58. return false;
  59. }
  60. /*
  61. send a command and offset
  62. */
  63. void AP_RAMTRON::send_offset(uint8_t cmd, uint32_t offset)
  64. {
  65. if (ramtron_ids[id].addrlen == 3) {
  66. uint8_t b[4] = { cmd, uint8_t((offset>>16)&0xFF), uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
  67. dev->transfer(b, sizeof(b), nullptr, 0);
  68. } else /* len 2 */ {
  69. uint8_t b[3] = { cmd, uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
  70. dev->transfer(b, sizeof(b), nullptr, 0);
  71. }
  72. }
  73. // read from device
  74. bool AP_RAMTRON::read(uint32_t offset, uint8_t *buf, uint32_t size)
  75. {
  76. const uint8_t maxread = 128;
  77. while (size > maxread) {
  78. if (!read(offset, buf, maxread)) {
  79. return false;
  80. }
  81. offset += maxread;
  82. buf += maxread;
  83. size -= maxread;
  84. }
  85. WITH_SEMAPHORE(dev->get_semaphore());
  86. dev->set_chip_select(true);
  87. send_offset(RAMTRON_READ, offset);
  88. // get data
  89. dev->transfer(nullptr, 0, buf, size);
  90. dev->set_chip_select(false);
  91. return true;
  92. }
  93. // write to device
  94. bool AP_RAMTRON::write(uint32_t offset, const uint8_t *buf, uint32_t size)
  95. {
  96. WITH_SEMAPHORE(dev->get_semaphore());
  97. // write enable
  98. uint8_t r = RAMTRON_WREN;
  99. dev->transfer(&r, 1, nullptr, 0);
  100. dev->set_chip_select(true);
  101. send_offset(RAMTRON_WRITE, offset);
  102. dev->transfer(buf, size, nullptr, 0);
  103. dev->set_chip_select(false);
  104. return true;
  105. }