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 29 { 0x24, 0x00, 128, 3},
30 { 0x24, 0x01, 128, 3},
31 { 0x25, 0x08, 256, 3},
32 { 0x26, 0x08, 512, 3},
33 { 0x27, 0x03, 128, 3},
46 uint8_t manufacturer[6];
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);
75 uint8_t b[4] = { cmd, uint8_t((offset>>16)&0xFF), uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
78 uint8_t b[3] = { cmd, uint8_t((offset>>8)&0xFF), uint8_t(offset&0xFF) };
86 const uint8_t maxread = 128;
87 while (size > maxread) {
88 if (!
read(offset, buf, maxread)) {
bool write(uint32_t offset, const uint8_t *buf, uint32_t size)
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
AP_HAL::UARTDriver * console
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
bool read(uint32_t offset, uint8_t *buf, uint32_t size)
virtual void printf(const char *,...) FMT_PRINTF(2
virtual OwnPtr< SPIDevice > get_device(const char *name)
virtual Semaphore * get_semaphore() override=0
void send_offset(uint8_t cmd, uint32_t offset)
virtual bool set_chip_select(bool set)
AP_HAL::SPIDeviceManager * spi
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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)
static const struct ramtron_id ramtron_ids[]