AP_HAL_AVR: remove Dataflash driver

This commit is contained in:
Pat Hickey 2012-12-07 20:58:35 -08:00 committed by Andrew Tridgell
parent 9cee6cc941
commit cb70590227
11 changed files with 1 additions and 1161 deletions

View File

@ -9,7 +9,6 @@
#include "SPIDriver.h"
#include "AnalogIn.h"
#include "Storage.h"
#include "Dataflash.h"
#include "Console.h"
#include "GPIO.h"
#include "RCInput.h"
@ -34,8 +33,6 @@ static APM1SPIDeviceManager apm1SPIDriver;
static APM2SPIDeviceManager apm2SPIDriver;
static AVRAnalogIn avrAnalogIn;
static AVREEPROMStorage avrEEPROMStorage;
static APM1Dataflash apm1Dataflash;
static APM2Dataflash apm2Dataflash;
static AVRConsoleDriver consoleDriver;
static AVRGPIO avrGPIO;
static APM1RCInput apm1RCInput;
@ -53,7 +50,6 @@ const HAL_AVR AP_HAL_AVR_APM1(
&apm1SPIDriver,
&avrAnalogIn,
&avrEEPROMStorage,
&apm1Dataflash,
&consoleDriver,
&avrGPIO,
&apm1RCInput,
@ -69,7 +65,6 @@ const HAL_AVR AP_HAL_AVR_APM2(
&apm2SPIDriver,
&avrAnalogIn,
&avrEEPROMStorage,
&apm2Dataflash,
&consoleDriver,
&avrGPIO,
&apm2RCInput,

View File

@ -15,9 +15,6 @@ namespace AP_HAL_AVR {
class ADCSource;
class AVRAnalogIn;
class AVREEPROMStorage;
class CommonDataflash;
class APM1Dataflash;
class APM2Dataflash;
class AVRConsoleDriver;
class AVRGPIO;
class AVRDigitalSource;

View File

@ -1,139 +0,0 @@
#ifndef __AP_HAL_AVR_DATAFLASH_H__
#define __AP_HAL_AVR_DATAFLASH_H__
#include <AP_HAL.h>
#include "AP_HAL_AVR_Namespace.h"
/* CommonDataflash: A partial concrete class providing the common
* implementations for most of the AP_HAL::Dataflash methods. */
class AP_HAL_AVR::CommonDataflash : public AP_HAL::Dataflash {
public:
/* Implementation-specific public methods (re-exported from AP_Dataflash) */
virtual void init(void *implspecific) = 0;
virtual void read_mfg_id() = 0;
virtual bool media_present() = 0;
/* Concrete public methods: */
uint16_t num_pages() { return _num_pages; }
uint8_t mfg_id() { return _mfg; }
uint16_t device_id() { return _device; }
uint16_t get_page() { return _read_page_addr - 1; }
uint16_t get_write_page() { return _page_addr; }
void erase_all();
bool need_erase();
void start_write(int16_t page);
void finish_write();
void write_byte(uint8_t data);
void write_word(uint16_t data);
void write_dword(uint32_t data);
void start_read(int16_t page);
uint8_t read_byte();
uint16_t read_word();
uint32_t read_dword();
void set_file(uint16_t filenum);
uint16_t get_file() { return _file_num; }
uint16_t get_file_page() { return _file_page; }
int16_t find_last_log();
void get_log_boundaries(uint8_t log,
int16_t &startpage, int16_t &endpage);
uint8_t get_num_logs();
void start_new_log();
protected:
/* Implementation-specific private methods: */
virtual void _wait_ready() = 0;
virtual void _page_to_buffer(uint8_t buffer_num, uint16_t page_addr) = 0;
virtual void _buffer_to_page(uint8_t buffer_num, uint16_t page_addr,
bool wait) = 0;
virtual void _page_erase(uint16_t page_addr) = 0;
virtual void _block_erase(uint16_t block_addr) = 0;
virtual void _chip_erase() = 0;
virtual void _buffer_write(uint8_t buffer_num, uint16_t page_addr,
uint8_t data) = 0;
virtual uint8_t _buffer_read(uint8_t buffer_num, uint16_t page_addr) = 0;
/* Concrete private methods: */
int16_t _find_last_page();
int16_t _find_last_page_of_log(uint16_t log_num);
bool _check_wrapped();
/* Instance variables: */
uint8_t _buffer_num;
uint8_t _read_buffer_num;
uint16_t _buffer_idx;
uint16_t _read_buffer_idx;
uint16_t _page_addr;
uint16_t _read_page_addr;
bool _stop_write;
uint16_t _file_num;
uint16_t _file_page;
/* Instance variables which should be initialized by the child class: */
uint8_t _mfg;
uint16_t _device;
uint16_t _page_size;
uint16_t _num_pages;
};
/* APM1Dataflash and APM2Dataflash: fully concrete classes implementing
* the remaining methods left virtual by CommonDataflash.
*/
class AP_HAL_AVR::APM1Dataflash : public AP_HAL_AVR::CommonDataflash {
public:
void init(void* spiDevice);
void read_mfg_id();
bool media_present();
private:
void _wait_ready();
void _page_to_buffer(uint8_t buffer_num, uint16_t page_addr);
void _buffer_to_page(uint8_t buffer_num, uint16_t page_addr, bool wait);
void _page_erase(uint16_t page_addr);
void _block_erase(uint16_t block_addr);
void _chip_erase();
void _buffer_write(uint8_t buffer_num, uint16_t page_addr, uint8_t data);
uint8_t _buffer_read(uint8_t buffer_num, uint16_t page_addr);
uint8_t _read_status_reg();
uint8_t _read_status();
AP_HAL::SPIDeviceDriver *_spi;
};
class AP_HAL_AVR::APM2Dataflash : public AP_HAL_AVR::CommonDataflash {
public:
void init(void* spiDevice);
void read_mfg_id();
bool media_present();
private:
void _wait_ready();
void _page_to_buffer(uint8_t buffer_num, uint16_t page_addr);
void _buffer_to_page(uint8_t buffer_num, uint16_t page_addr, bool wait);
void _page_erase(uint16_t page_addr);
void _block_erase(uint16_t block_addr);
void _chip_erase();
void _buffer_write(uint8_t buffer_num, uint16_t page_addr, uint8_t data);
uint8_t _buffer_read(uint8_t buffer_num, uint16_t page_addr);
uint8_t _read_status_reg();
uint8_t _read_status();
AP_HAL::SPIDeviceDriver *_spi;
};
#endif // __AP_HAL_AVR_DATAFLASH_H__

View File

@ -1,212 +0,0 @@
#include <AP_HAL.h>
#include "Dataflash.h"
using namespace AP_HAL_AVR;
extern const AP_HAL::HAL& hal;
/* flash size */
#define DF_LAST_PAGE 4096
#define DF_RESET_PIN 31 /* (PC6) */
/* AT45DB161D commands (from datasheet) */
#define DF_TRANSFER_PAGE_TO_BUFFER_1 0x53
#define DF_TRANSFER_PAGE_TO_BUFFER_2 0x55
#define DF_STATUS_REGISTER_READ 0xD7
#define DF_READ_MANUFACTURER_AND_DEVICE_ID 0x9F
#define DF_PAGE_READ 0xD2
#define DF_BUFFER_1_READ 0xD4
#define DF_BUFFER_2_READ 0xD6
#define DF_BUFFER_1_WRITE 0x84
#define DF_BUFFER_2_WRITE 0x87
#define DF_BUFFER_1_TO_PAGE_WITH_ERASE 0x83
#define DF_BUFFER_2_TO_PAGE_WITH_ERASE 0x86
#define DF_PAGE_ERASE 0x81
#define DF_BLOCK_ERASE 0x50
#define DF_SECTOR_ERASE 0x7C
#define DF_CHIP_ERASE_0 0xC7
#define DF_CHIP_ERASE_1 0x94
#define DF_CHIP_ERASE_2 0x80
#define DF_CHIP_ERASE_3 0x9A
void APM1Dataflash::init(void* machtnichts) {
hal.gpio->pinMode(DF_RESET_PIN, GPIO_OUTPUT);
/* Reset the dataflash chip */
hal.gpio->write(DF_RESET_PIN, 0);
hal.scheduler->delay(1);
hal.gpio->write(DF_RESET_PIN, 1);
_spi = hal.spi->device(AP_HAL::SPIDevice_Dataflash);
_num_pages = DF_LAST_PAGE - 1;
uint8_t status = _read_status_reg();
_page_size = (status & 0x01) ? 512 : 528;
}
void APM1Dataflash::read_mfg_id() {
_spi->cs_assert();
_spi->transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
_mfg = _spi->transfer(0xFF);
_device = _spi->transfer(0xFF);
_device = (_device << 8) | _spi->transfer(0xFF);
/* fourth byte is dont care */
_spi->transfer(0xFF);
_spi->cs_release();
}
bool APM1Dataflash::media_present() {
return true;
}
void APM1Dataflash::_wait_ready() {
while(!_read_status());
}
void APM1Dataflash::_page_to_buffer(uint8_t buffer_num, uint16_t page_addr) {
_spi->cs_assert();
if (_buffer_num == 1) {
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
} else {
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
}
if (_page_size == 512) {
_spi->transfer( page_addr >> 7 );
_spi->transfer( page_addr << 1 );
} else {
_spi->transfer( page_addr >> 6 );
_spi->transfer( page_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM1Dataflash::_buffer_to_page(uint8_t buffer_num, uint16_t page_addr, bool wait) {
_spi->cs_assert();
if (_buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
} else {
_spi->transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
}
if (_page_size == 512) {
_spi->transfer( page_addr >> 7 );
_spi->transfer( page_addr << 1 );
} else {
_spi->transfer( page_addr >> 6 );
_spi->transfer( page_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
if (wait) {
_wait_ready();
}
}
void APM1Dataflash::_page_erase(uint16_t page_addr) {
_spi->cs_assert();
_spi->transfer(DF_PAGE_ERASE);
if (_page_size == 512) {
_spi->transfer( page_addr >> 7 );
_spi->transfer( page_addr << 1 );
} else {
_spi->transfer( page_addr >> 6 );
_spi->transfer( page_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM1Dataflash::_block_erase(uint16_t block_addr) {
_spi->cs_assert();
_spi->transfer(DF_BLOCK_ERASE);
if (_page_size == 512) {
_spi->transfer( block_addr >> 7 );
_spi->transfer( block_addr << 1 );
} else {
_spi->transfer( block_addr >> 6 );
_spi->transfer( block_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM1Dataflash::_chip_erase() {
_spi->cs_assert();
_spi->transfer(DF_CHIP_ERASE_0);
_spi->transfer(DF_CHIP_ERASE_1);
_spi->transfer(DF_CHIP_ERASE_2);
_spi->transfer(DF_CHIP_ERASE_3);
_spi->cs_release();
while(!_read_status()) {
hal.scheduler->delay(1);
}
}
void APM1Dataflash::_buffer_write(uint8_t buffer_num, uint16_t page_addr, uint8_t data) {
_spi->cs_assert();
if (buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_WRITE);
} else {
_spi->transfer(DF_BUFFER_2_WRITE);
}
/* Don't care */
_spi->transfer(0);
/* Internal buffer address */
_spi->transfer((uint8_t)(page_addr >> 8));
_spi->transfer((uint8_t)(page_addr & 0xFF));
/* Byte to write */
_spi->transfer(data);
_spi->cs_release();
}
uint8_t APM1Dataflash::_buffer_read(uint8_t buffer_num, uint16_t page_addr) {
_spi->cs_assert();
if (buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_READ);
} else {
_spi->transfer(DF_BUFFER_2_READ);
}
/* Don't care */
_spi->transfer(0);
/* Internal buffer address */
_spi->transfer((uint8_t)(page_addr >> 8));
_spi->transfer((uint8_t)(page_addr & 0xFF));
/* Don't care */
_spi->transfer(0);
/* Read data byte */
uint8_t res = _spi->transfer(0);
_spi->cs_release();
return res;
}
inline uint8_t APM1Dataflash::_read_status_reg() {
_spi->cs_assert();
_spi->transfer(DF_STATUS_REGISTER_READ);
/* Read the first byte of the result */
uint8_t res = _spi->transfer(0);
_spi->cs_release();
return res;
}
inline uint8_t APM1Dataflash::_read_status() {
/* Busy status is the top bit of the status register */
return _read_status_reg() & 0x80;
}

View File

@ -1,250 +0,0 @@
#include <avr/io.h>
#include <AP_HAL.h>
#include "Dataflash.h"
using namespace AP_HAL_AVR;
extern const AP_HAL::HAL& hal;
/* Connected to USART3 in SPI mode */
#define DF_RESET_PIN 41 /* RESET (PG0) */
#define DF_CARDDETECT_PIN 33 /* PC4 */
// AT45DB321D Commands (from Datasheet)
#define DF_TRANSFER_PAGE_TO_BUFFER_1 0x53
#define DF_TRANSFER_PAGE_TO_BUFFER_2 0x55
#define DF_STATUS_REGISTER_READ 0xD7
#define DF_READ_MANUFACTURER_AND_DEVICE_ID 0x9F
#define DF_PAGE_READ 0xD2
#define DF_BUFFER_1_READ 0xD4
#define DF_BUFFER_2_READ 0xD6
#define DF_BUFFER_1_WRITE 0x84
#define DF_BUFFER_2_WRITE 0x87
#define DF_BUFFER_1_TO_PAGE_WITH_ERASE 0x83
#define DF_BUFFER_2_TO_PAGE_WITH_ERASE 0x86
#define DF_PAGE_ERASE 0x81
#define DF_BLOCK_ERASE 0x50
#define DF_SECTOR_ERASE 0x7C
#define DF_CHIP_ERASE_0 0xC7
#define DF_CHIP_ERASE_1 0x94
#define DF_CHIP_ERASE_2 0x80
#define DF_CHIP_ERASE_3 0x9A
#ifdef DEBUG
#define LOGD(format, ...) do { hal.console->printf_P(PSTR("DBG/Dataflash: "format), __VA_ARGS__); } while (0)
#else
#define LOGD(format, ...) do {} while(0)
#endif
void APM2Dataflash::init(void* machtnichts) {
/* setup gpio pins */
hal.gpio->pinMode(DF_RESET_PIN, GPIO_OUTPUT);
hal.gpio->pinMode(DF_CARDDETECT_PIN, GPIO_INPUT);
/* Reset device */
hal.gpio->write(DF_RESET_PIN, 0);
hal.scheduler->delay(1);
hal.gpio->write(DF_RESET_PIN, 1);
_spi = hal.spi->device(AP_HAL::SPIDevice_Dataflash);
uint8_t status = _read_status_reg();
_page_size = (status & 0x01) ? 512 : 528;
LOGD("_page_size set to %d\r\n", _page_size);
read_mfg_id();
/* If no card is present, MISO is usually either constant high or constant
* low. Result is all 0 or all 1s for _mfg and _device.
*/
if ((_mfg == 0 && _device == 0)
||(_mfg == 0xFF && _device == 0xFFFF)) {
_num_pages = 0;
return;
}
/* from page 22 of the spec, density code decoder: */
uint8_t density_code = (_device >> 8) & 0x1F;
if (density_code == 0x7) {
/* 32 Mbit */
_num_pages = 8191;
} else if (density_code == 0x06) {
/* 16 Mbit */
_num_pages = 4095;
} else {
/* Unknown */
_num_pages = 0;
}
}
void APM2Dataflash::read_mfg_id() {
_spi->cs_assert();
_spi->transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
_mfg = _spi->transfer(0xFF);
_device = _spi->transfer(0xFF);
_device = (_device << 8) | _spi->transfer(0xFF);
_spi->transfer(0xFF);
_spi->cs_release();
}
bool APM2Dataflash::media_present() {
/* if init detected a df chip, it set _num_pages > 0. */
return _num_pages > 0;
}
void APM2Dataflash::_wait_ready() {
while(!_read_status());
}
void APM2Dataflash::_page_to_buffer(uint8_t buffer_num, uint16_t page_addr) {
LOGD("_page_to_buffer: buf: %d page: %d\r\n", (int) buffer_num, page_addr);
_spi->cs_assert();
if (_buffer_num == 1) {
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
} else {
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
}
if (_page_size == 512) {
_spi->transfer((uint8_t)(page_addr >> 7));
_spi->transfer((uint8_t)(page_addr << 1));
} else {
_spi->transfer((uint8_t)(page_addr >> 6));
_spi->transfer((uint8_t)(page_addr << 2));
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM2Dataflash::_buffer_to_page(uint8_t buffer_num, uint16_t page_addr, bool wait) {
LOGD("_buffer_to_page buf: %d, page: %d\r\n",
(int) buffer_num, page_addr);
_spi->cs_assert();
if (_buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
} else {
_spi->transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
}
if (_page_size == 512) {
_spi->transfer((uint8_t)(page_addr >> 7));
_spi->transfer((uint8_t)(page_addr << 1));
} else {
_spi->transfer((uint8_t)(page_addr >> 6));
_spi->transfer((uint8_t)(page_addr << 2));
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
if (wait) {
_wait_ready();
}
}
void APM2Dataflash::_page_erase(uint16_t page_addr) {
_spi->cs_assert();
_spi->transfer(DF_PAGE_ERASE);
if (_page_size == 512) {
_spi->transfer( page_addr >> 7 );
_spi->transfer( page_addr << 1 );
} else {
_spi->transfer( page_addr >> 6 );
_spi->transfer( page_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM2Dataflash::_block_erase(uint16_t block_addr) {
LOGD("_block_erase %d\r\n", block_addr);
_spi->cs_assert();
_spi->transfer(DF_BLOCK_ERASE);
if (_page_size == 512) {
_spi->transfer( block_addr >> 7 );
_spi->transfer( block_addr << 1 );
} else {
_spi->transfer( block_addr >> 6 );
_spi->transfer( block_addr << 2 );
}
/* finally send one dont care byte */
_spi->transfer(0x00);
_spi->cs_release();
_wait_ready();
}
void APM2Dataflash::_chip_erase() {
_spi->cs_assert();
_spi->transfer(DF_CHIP_ERASE_0);
_spi->transfer(DF_CHIP_ERASE_1);
_spi->transfer(DF_CHIP_ERASE_2);
_spi->transfer(DF_CHIP_ERASE_3);
_spi->cs_release();
while(!_read_status()) {
hal.scheduler->delay(1);
}
}
void APM2Dataflash::_buffer_write(uint8_t buffer_num, uint16_t page_addr, uint8_t data) {
LOGD("_buffer_write buf: %d page: %d data: %d\r\n",
(int) buffer_num, page_addr, (int) data);
_spi->cs_assert();
if (buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_WRITE);
} else {
_spi->transfer(DF_BUFFER_2_WRITE);
}
/* Don't care */
_spi->transfer(0);
/* Internal buffer address */
_spi->transfer((uint8_t)(page_addr >> 8));
_spi->transfer((uint8_t)(page_addr & 0xFF));
/* Byte to write */
_spi->transfer(data);
_spi->cs_release();
}
uint8_t APM2Dataflash::_buffer_read(uint8_t buffer_num, uint16_t page_addr) {
_spi->cs_assert();
if (buffer_num == 1) {
_spi->transfer(DF_BUFFER_1_READ);
} else {
_spi->transfer(DF_BUFFER_2_READ);
}
/* Don't care */
_spi->transfer(0);
/* Internal buffer address */
_spi->transfer((uint8_t)(page_addr >> 8));
_spi->transfer((uint8_t)(page_addr & 0xFF));
/* Don't care */
_spi->transfer(0);
/* Read data byte */
uint8_t res = _spi->transfer(0);
_spi->cs_release();
LOGD("_buffer_read num: %d pageaddr: %d result: %d\r\n",
(int) buffer_num, (int) page_addr, (int) res);
return res;
}
inline uint8_t APM2Dataflash::_read_status_reg() {
_spi->cs_assert();
_spi->transfer(DF_STATUS_REGISTER_READ);
/* Read the first byte of the result */
uint8_t res = _spi->transfer(0);
_spi->cs_release();
return res;
}
inline uint8_t APM2Dataflash::_read_status() {
/* Busy status is the top bit of the status register */
return _read_status_reg() & 0x80;
}

View File

@ -1,365 +0,0 @@
#include <AP_HAL.h>
#include "Dataflash.h"
using namespace AP_HAL_AVR;
extern const AP_HAL::HAL& hal;
// 0: When reach the end page stop, 1: Start overwriting from page 1
#define DF_OVERWRITE_DATA true
void CommonDataflash::erase_all() {
for (uint16_t i = 1; i <= (_num_pages+1)/8; i++) {
_block_erase(i);
hal.scheduler->delay(1);
}
start_write(_num_pages+1);
write_dword(DF_LOGGING_FORMAT);
finish_write();
}
bool CommonDataflash::need_erase() {
start_read(_num_pages+1);
uint32_t fmtbyte = read_dword();
if (fmtbyte != DF_LOGGING_FORMAT) {
hal.console->printf_P(
PSTR("logging fmt got %lX expected %lX\r\n"),
fmtbyte, DF_LOGGING_FORMAT);
return true;
} else {
return false;
}
}
void CommonDataflash::start_write(int16_t page) {
_buffer_num = 1;
_buffer_idx = 4;
_page_addr = page;
_stop_write = false;
_wait_ready();
_buffer_write(_buffer_num, 0, _file_num >> 8 );
_buffer_write(_buffer_num, 1, _file_num&0xFF );
_buffer_write(_buffer_num, 2, _file_page >> 8 );
_buffer_write(_buffer_num, 3, _file_page&0xFF );
}
void CommonDataflash::finish_write() {
_buffer_idx = 0;
/* Write buffer to memory, no wait. */
_buffer_to_page(_buffer_num, _page_addr, false);
_page_addr++;
if (DF_OVERWRITE_DATA) {
if (_page_addr > _num_pages) {
_page_addr = 1;
}
} else {
if (_page_addr > _num_pages) {
_stop_write = true;
}
}
/* switch buffer to continue writing */
_buffer_num = (_buffer_num == 1) ? 2 : 1;
}
void CommonDataflash::write_byte(uint8_t data) {
if (_stop_write) return;
_buffer_write( _buffer_num, _buffer_idx, data );
_buffer_idx++;
/* end of buffer? */
if ( _buffer_idx > _page_size) {
/* 4 bytes for filenumber, filepage */
_buffer_idx = 4;
/* write buffer to memory, no waiting */
_buffer_to_page(_buffer_num, _page_addr, false);
_page_addr++;
if (DF_OVERWRITE_DATA) {
if (_page_addr > _num_pages) {
_page_addr = 1;
}
} else {
if (_page_addr > _num_pages) {
_stop_write = true;
}
}
/* switch buffer to continue writing */
_buffer_num = (_buffer_num == 1) ? 2 : 1;
/* We are starting a new page. write filenumber and filepage. */
_buffer_write(_buffer_num, 0, _file_num >> 8 );
_buffer_write(_buffer_num, 1, _file_num&0xFF );
_buffer_write(_buffer_num, 2, _file_page >> 8 );
_buffer_write(_buffer_num, 3, _file_page&0xFF );
}
}
void CommonDataflash::write_word(uint16_t data) {
write_byte( data >> 8 ); /* high byte */
write_byte( data & 0xFF ); /* low byte */
}
void CommonDataflash::write_dword(uint32_t data) {
write_byte( data >> 24 ); /* high byte */
write_byte( data >> 16 );
write_byte( data >> 8 );
write_byte( data & 0xFF ); /* low byte */
}
void CommonDataflash::start_read(int16_t page) {
_read_buffer_num = 1;
_read_buffer_idx = 4;
_read_page_addr = page;
_wait_ready();
/* Write memory page to buffer. */
_page_to_buffer(_read_buffer_num, _read_page_addr);
_read_page_addr++;
/* We are starting a new page. Read file number and file page */
_file_num = _buffer_read(_read_buffer_num, 0);
_file_num = (_file_num << 8) | _buffer_read(_read_buffer_num, 1);
_file_page = _buffer_read(_read_buffer_num, 2);
_file_page = (_file_page << 8 ) | _buffer_read(_read_buffer_num, 3);
}
uint8_t CommonDataflash::read_byte() {
_wait_ready();
uint8_t result = _buffer_read( _read_buffer_num, _read_buffer_idx);
_read_buffer_idx++;
/* Check if we reached the end of buffer */
if ( _read_buffer_idx >= _page_size ) {
/* 4 bytes for file number, file page */
_read_buffer_idx = 4;
/* Write memory page to buffer */
_page_to_buffer(_read_buffer_num, _read_page_addr);
_read_page_addr++;
/* If we reach the end o fmemory, start from the beginning */
if (_read_page_addr > _num_pages) {
_read_page_addr = 0;
}
/* We are starting a new page. read file number and file page. */
_file_num = _buffer_read(_read_buffer_num, 0);
_file_num = (_file_num << 8) | _buffer_read(_read_buffer_num, 1);
_file_page = _buffer_read(_read_buffer_num, 2);
_file_page = (_file_page << 8) | _buffer_read(_read_buffer_num, 3);
}
return result;
}
uint16_t CommonDataflash::read_word() {
uint16_t result = read_byte(); /* High byte */
result = (result << 8) | read_byte(); /* Low byte */
return result;
}
uint32_t CommonDataflash::read_dword() {
uint32_t result = read_byte(); /* High byte */
result = (result << 8) | read_byte();
result = (result << 8) | read_byte();
result = (result << 8) | read_byte(); /* Low byte */
return result;
}
void CommonDataflash::set_file(uint16_t filenum) {
_file_num = filenum;
_file_page = 1;
}
int16_t CommonDataflash::find_last_log() {
int16_t last_page = _find_last_page();
/* start_read will populate _file_num. */
start_read(last_page);
return _file_num;
}
void CommonDataflash::get_log_boundaries(uint8_t log,
int16_t &startpage, int16_t &endpage) {
/* XXX Here be dragons. I transliterated this code from DataFlash_Class::
* get_log_boundaries - pch 04sept12 */
int16_t num_logs = get_num_logs();
if ( num_logs == 1 ) {
/* Read the file number from the last page. */
start_read(_num_pages);
/* invariant: find_last_page_of_log does not change _file_num */
endpage = _find_last_page_of_log((uint16_t)log);
if (_file_num == 0xFFFF) {
startpage = 1;
} else {
startpage = endpage + 1;
}
} else {
if (log == 1) {
start_read(_num_pages);
if (_file_num == 0xFFFF) {
startpage = 1;
} else {
startpage = _find_last_page() + 1;
}
} else {
if ( log == (find_last_log() - num_logs + 1) ) {
startpage = _find_last_page() + 1;
} else {
int16_t look = num_logs - 1;
do { startpage = _find_last_page_of_log(look) + 1;
look--;
} while (startpage <= 0 && look >= 1);
}
}
}
if (startpage == ( (int16_t) _num_pages + 1 ) || startpage == 0 ) {
startpage = 1;
}
endpage = _find_last_page_of_log((uint16_t) log);
if (endpage <= 0) {
endpage = startpage;
}
}
uint8_t CommonDataflash::get_num_logs() {
/* First try _find_last_page */
int16_t last_page = _find_last_page();
if (last_page == 1) {
return 0;
}
/* Read _file_num from page 1 */
start_read(1);
if (_file_num == 0xFFFF) {
return 0;
}
/* Read _file_num from last page */
start_read(last_page);
uint16_t last = get_file();
/* XXX bounds check on last_page+2? */
/* Read _file_num from last_page+2 */
start_read(last_page+2);
uint16_t first = _file_num;
if (first > last) {
/* We wrapped aroung, so get the file_num from page 1. */
start_read(1);
first = _file_num;
}
if (last == first) {
return 1;
} else {
return (last - first + 1);
}
}
void CommonDataflash::start_new_log() {
uint16_t last_page = _find_last_page();
start_read(last_page);
/* XXX I'm pretty sure there's a bug here - find_last_log will overwrite
* the _file_num invariant from start_read(last_page).
* However, I'm reproducing the existing DataFlash_Class faithfully. */
if (find_last_log() == 0 || _file_num == 0xFFFF) {
set_file(1);
start_write(1);
return;
}
/* Check for log of length 1 page and suppress */
if (get_file() <= 1) {
/* Last log is too short, reuse its number */
set_file(_file_num);
/* and overwrite it */
start_write(last_page);
} else {
/* XXX shouldn't we have checked (== 0xFFFF) before using last_page
* in the case above? */
if (last_page == 0xFFFF) {
last_page = 0;
}
set_file(get_file() + 1);
start_write(last_page + 1);
}
}
int16_t CommonDataflash::_find_last_page() {
uint16_t top = _num_pages;
uint16_t bottom = 1;
start_read(bottom);
uint32_t bottom_hash = ((uint32_t) _file_num) << 16 | _file_page;
while ( top - bottom > 1 ) {
uint16_t look = (top + bottom) / 2;
start_read(look);
uint32_t look_hash = ((uint32_t) _file_num) << 16 | _file_page;
if (look_hash >= 0xFFFF0000) {
look_hash = 0;
}
if (look_hash < bottom_hash) {
/* move down */
top = look;
} else {
/* move up */
bottom = look;
bottom_hash = look_hash;
}
}
start_read(top);
uint32_t top_hash = ((uint32_t) _file_num) << 16 | _file_page;
if (top_hash >= 0xFFFF0000) {
top_hash = 0;
}
if (top_hash > bottom_hash) {
return top;
} else {
return bottom;
}
}
int16_t CommonDataflash::_find_last_page_of_log(uint16_t log_num) {
uint16_t bottom, top;
if (_check_wrapped()) {
start_read(1);
bottom = _file_num;
if (bottom > log_num) {
bottom = _find_last_page();
top = _num_pages;
} else {
bottom = 1;
top = _find_last_page();
}
} else {
bottom = 1;
top = _find_last_page();
}
uint32_t check_hash = ((int32_t) log_num) << 16 | 0xFFFF;
while (top - bottom > 1) {
uint16_t look = (top + bottom) / 2;
start_read(look);
uint32_t look_hash = ((uint32_t) _file_num) << 16 | _file_page;
if (look_hash >= 0xFFFF0000) {
look_hash = 0;
}
if (look_hash > check_hash) {
top = look; /* move down */
} else {
bottom = look; /* move up */
}
}
start_read(top);
if (_file_num == log_num) {
return top;
}
start_read(bottom);
if (_file_num == log_num) {
return bottom;
}
return -1;
}
bool CommonDataflash::_check_wrapped() {
start_read(_num_pages);
return (_file_num != 0xFFFF);
}

View File

@ -21,7 +21,6 @@ public:
AP_HAL::SPIDeviceManager* _spi,
AP_HAL::AnalogIn* _analogin,
AP_HAL::Storage* _storage,
AP_HAL::Dataflash* _dataflash,
AP_HAL::ConsoleDriver* _console,
AP_HAL::GPIO* _gpio,
AP_HAL::RCInput* _rcin,
@ -29,7 +28,7 @@ public:
AP_HAL::Scheduler* _scheduler)
: AP_HAL::HAL( _uartA, _uartB, _uartC,
_i2c, _spi, _analogin, _storage,
_dataflash, _console, _gpio, _rcin,
_console, _gpio, _rcin,
_rcout, _scheduler) {}
void init(void* opts) const;

View File

@ -1,184 +0,0 @@
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
bool dbg = true;
void erase() {
hal.console->println("Erasing dataflash");
hal.dataflash->erase_all();
}
void readback_page(int i);
void single_page_readwrite() {
hal.console->println("Writing simple sequence to page 1");
hal.dataflash->start_write(1);
hal.dataflash->write_byte(1);
hal.dataflash->write_byte(2);
hal.dataflash->write_byte(3);
hal.dataflash->write_byte(4);
hal.dataflash->write_byte(5);
/* Fill up the rest of the page with garbage */
for (int i = 0; i < 600; i++) {
hal.dataflash->write_byte(0x77);
}
hal.dataflash->finish_write();
hal.scheduler->delay(100);
readback_page(1);
}
void readback_page(int i) {
hal.console->printf_P(PSTR("Reading back sequence from page %d\r\n"), i);
hal.dataflash->start_read(i);
uint8_t v1 = hal.dataflash->read_byte();
uint8_t v2 = hal.dataflash->read_byte();
uint8_t v3 = hal.dataflash->read_byte();
uint8_t v4 = hal.dataflash->read_byte();
uint8_t v5 = hal.dataflash->read_byte();
uint8_t v6 = hal.dataflash->read_byte();
uint8_t v7 = hal.dataflash->read_byte();
hal.console->printf_P(PSTR("vals on page %d: %d %d %d %d %d 0x%x 0x%x\r\n"),
i, (int) v1, (int) v2, (int) v3, (int) v4, (int) v5,
(int) v6, (int) v7);
}
void two_page_readwrite() {
hal.console->println("Writing simple sequence to page 1");
hal.dataflash->start_write(1);
hal.dataflash->write_byte(1);
hal.dataflash->write_byte(2);
hal.dataflash->write_byte(3);
hal.dataflash->write_byte(4);
hal.dataflash->write_byte(5);
/* Fill up the rest of the page with garbage */
for (int i = 0; i < 6; i++) {
hal.dataflash->write_byte(0x77);
}
hal.dataflash->finish_write();
hal.scheduler->delay(100);
readback_page(1);
hal.console->println("Writing simple sequence to page 2");
hal.dataflash->start_write(2);
hal.dataflash->write_byte(21);
hal.dataflash->write_byte(22);
hal.dataflash->write_byte(23);
hal.dataflash->write_byte(24);
hal.dataflash->write_byte(25);
/* Fill up the rest of the page with garbage */
for (int i = 0; i < 6; i++) {
hal.dataflash->write_byte(0x77);
}
hal.dataflash->finish_write();
hal.scheduler->delay(100);
readback_page(1);
readback_page(2);
hal.dataflash->start_write(3);
hal.dataflash->write_byte(99);
hal.dataflash->write_byte(99);
hal.dataflash->write_byte(99);
hal.dataflash->finish_write();
/* NOTE: getting rid of the above finish_write
fixup the upcoming reads: fetching page 1, 2 will work! and three is a
faithful read (255s if erased) */
hal.scheduler->delay(100);
readback_page(1);
readback_page(2);
readback_page(3);
}
void longtest_write() {
// We start to write some info (sequentialy) starting from page 1
// This is similar to what we will do...
hal.console->println("After testing perform erase before using hal.dataflash->for logging!");
hal.console->println("");
hal.console->println("Writing to flash... wait...");
hal.dataflash->start_write(1);
for (int i = 0; i < 40; i++) {
// Write 1000 packets...
// We write packets of binary data... (without worry about nothing more)
hal.dataflash->write_byte(0xA3);
hal.dataflash->write_byte(0x95);
hal.dataflash->write_word(2000 + i);
hal.dataflash->write_word(2001 + i);
hal.dataflash->write_word(2002 + i);
hal.dataflash->write_word(2003 + i);
hal.dataflash->write_dword((int32_t)i * 5000);
hal.dataflash->write_dword((int32_t)i * 16268);
hal.dataflash->write_byte(0xA2);// 2 bytes of checksum (example)
hal.dataflash->write_byte(0x4E);
hal.scheduler->delay(10);
}
hal.scheduler->delay(100);
}
void longtest_readback()
{
uint8_t tmp_byte1, tmp_byte2;
long tmp_long;
hal.console->println("Start reading page 1...");
hal.dataflash->start_read(1); // We start reading from page 1
for (int i = 0; i < 40; i++) { // Read 200 packets...
uint8_t sync1 = hal.dataflash->read_byte();
uint8_t sync2 = hal.dataflash->read_byte();
// Read 4 ints...
int16_t w1 = hal.dataflash->read_word();
int16_t w2 = hal.dataflash->read_word();
int16_t w3 = hal.dataflash->read_word();
int16_t w4 = hal.dataflash->read_word();
// Read 2 longs...
int32_t l1 = hal.dataflash->read_dword();
int32_t l2 = hal.dataflash->read_dword();
// Read the checksum...
int8_t cs1 = hal.dataflash->read_byte();
int8_t cs2 = hal.dataflash->read_byte();
hal.console->printf_P(PSTR("sync 0x%x 0x%x ints %d %d %d %d, "
"longs %d %d, cksm %d %d\r\n"),
(int) sync1, (int) sync2,
w1, w2, w3, w4,
l1, l2,
cs1, cs2);
}
}
void setup()
{
hal.dataflash->init(NULL);
hal.console->println("Dataflash Log Test 1.0");
hal.scheduler->delay(20);
hal.console->print("Manufacturer:");
hal.console->print((int)hal.dataflash->mfg_id());
hal.console->print(",");
hal.console->print((int)hal.dataflash->device_id());
hal.console->println();
erase();
// two_page_readwrite();
dbg = false;
longtest_write();
longtest_readback();
}
void loop () {}
AP_HAL_MAIN();

View File

@ -1 +0,0 @@
include ../../../AP_Common/Arduino.mk