2018-01-01 02:57:04 -04:00
|
|
|
/*
|
|
|
|
driver for RAMTRON FRAM persistent memory devices
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
class AP_RAMTRON {
|
|
|
|
public:
|
|
|
|
// initialise the driver
|
2020-05-11 03:01:17 -03:00
|
|
|
// this will retry RAMTRON_RETRIES times until successful
|
2018-01-01 02:57:04 -04:00
|
|
|
bool init(void);
|
|
|
|
|
|
|
|
// get size in bytes
|
2020-05-11 03:01:17 -03:00
|
|
|
uint32_t get_size(void) const { return (id == UINT8_MAX) ? 0 : ramtron_ids[id].size_kbyte * 1024UL; }
|
2018-01-01 02:57:04 -04:00
|
|
|
|
|
|
|
// read from device
|
2020-05-11 03:01:17 -03:00
|
|
|
// this will retry RAMTRON_RETRIES times until two successive reads return the same data
|
|
|
|
bool read(uint32_t offset, uint8_t * const buf, uint32_t size);
|
2018-01-01 02:57:04 -04:00
|
|
|
|
|
|
|
// write to device
|
2020-05-11 03:01:17 -03:00
|
|
|
bool write(uint32_t offset, uint8_t const * const buf, uint32_t size);
|
2018-01-01 02:57:04 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
|
|
|
|
|
2020-05-11 03:01:17 -03:00
|
|
|
enum class RDID_type :uint8_t {
|
|
|
|
Cypress,
|
|
|
|
Fujitsu,
|
|
|
|
};
|
|
|
|
|
2018-01-01 02:57:04 -04:00
|
|
|
struct ramtron_id {
|
2020-05-11 03:01:17 -03:00
|
|
|
uint8_t id1;
|
|
|
|
uint8_t id2;
|
2018-01-01 02:57:04 -04:00
|
|
|
uint16_t size_kbyte;
|
|
|
|
uint8_t addrlen;
|
2020-05-11 03:01:17 -03:00
|
|
|
RDID_type rdid_type;
|
2018-01-01 02:57:04 -04:00
|
|
|
};
|
|
|
|
static const struct ramtron_id ramtron_ids[];
|
2020-05-11 03:01:17 -03:00
|
|
|
uint8_t id = UINT8_MAX;
|
|
|
|
|
|
|
|
// perform a single device initialisation
|
|
|
|
bool _init(void);
|
|
|
|
// perform a single device read
|
|
|
|
bool _read(uint32_t offset, uint8_t * const buf, uint32_t size);
|
2018-01-01 02:57:04 -04:00
|
|
|
|
2020-05-11 03:01:17 -03:00
|
|
|
void send_offset(uint8_t cmd, uint32_t offset) const;
|
2018-01-01 02:57:04 -04:00
|
|
|
};
|