APM:Libraries
AP_RAMTRON.h
Go to the documentation of this file.
1 /*
2  driver for RAMTRON FRAM persistent memory devices
3  */
4 #pragma once
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_HAL/AP_HAL.h>
8 
9 class AP_RAMTRON {
10 public:
11  // initialise the driver
12  bool init(void);
13 
14  // get size in bytes
15  uint32_t get_size(void) const { return ramtron_ids[id].size_kbyte*1024UL; }
16 
17  // read from device
18  bool read(uint32_t offset, uint8_t *buf, uint32_t size);
19 
20  // write to device
21  bool write(uint32_t offset, const uint8_t *buf, uint32_t size);
22 
23 private:
25 
26  struct ramtron_id {
27  uint8_t id1, id2;
28  uint16_t size_kbyte;
29  uint8_t addrlen;
30  };
31  static const struct ramtron_id ramtron_ids[];
32  uint8_t id;
33 
34  // send offset of transfer
35  void send_offset(uint8_t cmd, uint32_t offset);
36 };
bool write(uint32_t offset, const uint8_t *buf, uint32_t size)
Definition: AP_RAMTRON.cpp:113
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
Definition: AP_RAMTRON.h:24
bool init(void)
Definition: AP_RAMTRON.cpp:38
uint32_t get_size(void) const
Definition: AP_RAMTRON.h:15
bool read(uint32_t offset, uint8_t *buf, uint32_t size)
Definition: AP_RAMTRON.cpp:84
void send_offset(uint8_t cmd, uint32_t offset)
Definition: AP_RAMTRON.cpp:72
uint8_t id
Definition: AP_RAMTRON.h:32
Common definitions and utility routines for the ArduPilot libraries.
static const struct ramtron_id ramtron_ids[]
Definition: AP_RAMTRON.h:31