APM:Libraries
AP_RAMTRON.cpp
Go to the documentation of this file.
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 
7 #include "AP_RAMTRON.h"
8 
9 extern const AP_HAL::HAL &hal;
10 
11 // register numbers
12 #define RAMTRON_RDID 0x9f
13 #define RAMTRON_READ 0x03
14 #define RAMTRON_RDSR 0x05
15 #define RAMTRON_WREN 0x06
16 #define RAMTRON_WRITE 0x02
17 
18 /*
19  list of supported devices. Thanks to NuttX ramtron driver
20  */
22  { 0x21, 0x00, 16, 2}, // FM25V01
23  { 0x21, 0x08, 16, 2}, // FM25V01A
24  { 0x22, 0x00, 32, 2}, // FM25V02
25  { 0x22, 0x08, 32, 2}, // FM25V02A
26  { 0x22, 0x01, 32, 2}, // FM25VN02
27  { 0x23, 0x00, 64, 2}, // FM25V05
28  { 0x23, 0x01, 64, 2}, // FM25VN05
29  { 0x24, 0x00, 128, 3}, // FM25V10
30  { 0x24, 0x01, 128, 3}, // FM25VN10
31  { 0x25, 0x08, 256, 3}, // FM25V20A
32  { 0x26, 0x08, 512, 3}, // CY15B104Q
33  { 0x27, 0x03, 128, 3}, // MB85RS1MT
34  { 0x05, 0x09, 32, 3}, // B85RS256B
35 };
36 
37 // initialise the driver
38 bool AP_RAMTRON::init(void)
39 {
40  dev = hal.spi->get_device("ramtron");
41  if (!dev || !dev->get_semaphore()->take(0)) {
42  return false;
43  }
44 
45  struct rdid {
46  uint8_t manufacturer[6];
47  uint8_t memory;
48  uint8_t id1;
49  uint8_t id2;
50  } rdid;
51  if (!dev->read_registers(RAMTRON_RDID, (uint8_t *)&rdid, sizeof(rdid))) {
52  dev->get_semaphore()->give();
53  return false;
54  }
55  dev->get_semaphore()->give();
56 
57  for (uint8_t i=0; i<ARRAY_SIZE(ramtron_ids); i++) {
58  if (ramtron_ids[i].id1 == rdid.id1 &&
59  ramtron_ids[i].id2 == rdid.id2) {
60  id = i;
61  return true;
62  }
63  }
64  hal.console->printf("Unknown RAMTRON manufacturer=%02x memory=%02x id1=%02x id2=%02x\n",
65  rdid.manufacturer[0], rdid.memory, rdid.id1, rdid.id2);
66  return false;
67 }
68 
69 /*
70  send a command and offset
71  */
72 void AP_RAMTRON::send_offset(uint8_t cmd, uint32_t offset)
73 {
74  if (ramtron_ids[id].addrlen == 3) {
75  uint8_t b[4] = { cmd, uint8_t((offset>>16)&0xFF), uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
76  dev->transfer(b, sizeof(b), nullptr, 0);
77  } else /* len 2 */ {
78  uint8_t b[3] = { cmd, uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
79  dev->transfer(b, sizeof(b), nullptr, 0);
80  }
81 }
82 
83 // read from device
84 bool AP_RAMTRON::read(uint32_t offset, uint8_t *buf, uint32_t size)
85 {
86  const uint8_t maxread = 128;
87  while (size > maxread) {
88  if (!read(offset, buf, maxread)) {
89  return false;
90  }
91  offset += maxread;
92  buf += maxread;
93  size -= maxread;
94  }
95 
96  if (!dev->get_semaphore()->take(0)) {
97  return false;
98  }
99  dev->set_chip_select(true);
100 
101  send_offset(RAMTRON_READ, offset);
102 
103  // get data
104  dev->transfer(nullptr, 0, buf, size);
105 
106  dev->set_chip_select(false);
107  dev->get_semaphore()->give();
108 
109  return true;
110 }
111 
112 // write to device
113 bool AP_RAMTRON::write(uint32_t offset, const uint8_t *buf, uint32_t size)
114 {
115  if (!dev->get_semaphore()->take(0)) {
116  return false;
117  }
118  // write enable
119  uint8_t r = RAMTRON_WREN;
120  dev->transfer(&r, 1, nullptr, 0);
121 
122  dev->set_chip_select(true);
123 
124  send_offset(RAMTRON_WRITE, offset);
125 
126  dev->transfer(buf, size, nullptr, 0);
127 
128  dev->set_chip_select(false);
129 
130  dev->get_semaphore()->give();
131  return true;
132 }
bool write(uint32_t offset, const uint8_t *buf, uint32_t size)
Definition: AP_RAMTRON.cpp:113
#define RAMTRON_WRITE
Definition: AP_RAMTRON.cpp:16
#define RAMTRON_RDID
Definition: AP_RAMTRON.cpp:12
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
Definition: AP_RAMTRON.h:24
bool init(void)
Definition: AP_RAMTRON.cpp:38
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool read(uint32_t offset, uint8_t *buf, uint32_t size)
Definition: AP_RAMTRON.cpp:84
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
virtual Semaphore * get_semaphore() override=0
void send_offset(uint8_t cmd, uint32_t offset)
Definition: AP_RAMTRON.cpp:72
virtual bool set_chip_select(bool set)
Definition: Device.h:214
virtual bool give()=0
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define RAMTRON_READ
Definition: AP_RAMTRON.cpp:13
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
static const struct ramtron_id ramtron_ids[]
Definition: AP_RAMTRON.h:31
#define RAMTRON_WREN
Definition: AP_RAMTRON.cpp:15