2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-08-10 02:24:12 -03:00
|
|
|
|
2014-08-25 13:18:48 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2014-08-10 02:24:12 -03:00
|
|
|
#include <assert.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
2015-10-22 14:34:40 -03:00
|
|
|
#include <inttypes.h>
|
2014-08-10 02:24:12 -03:00
|
|
|
#include <unistd.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <stdio.h>
|
2014-08-25 13:18:48 -03:00
|
|
|
#include "Storage.h"
|
2014-08-10 02:24:12 -03:00
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
|
|
|
/*
|
|
|
|
This stores 'eeprom' data on the FRAM, with a 4k size, and a
|
|
|
|
in-memory buffer. This keeps the latency down.
|
|
|
|
*/
|
|
|
|
|
|
|
|
// name the storage file after the sketch so you can use the same board
|
|
|
|
// card for ArduCopter and ArduPlane
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2015-10-20 18:13:25 -03:00
|
|
|
Storage_FRAM::Storage_FRAM():
|
2014-08-10 02:24:12 -03:00
|
|
|
_spi(NULL),
|
2014-08-25 13:18:48 -03:00
|
|
|
_spi_sem(NULL)
|
2014-08-10 02:24:12 -03:00
|
|
|
{}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage_FRAM::_storage_create(void)
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
|
|
|
|
|
|
|
int fd = open();
|
|
|
|
hal.console->println("Storage: FRAM is getting reset to default values");
|
|
|
|
|
|
|
|
if (fd == -1) {
|
|
|
|
hal.scheduler->panic("Failed to load FRAM");
|
|
|
|
}
|
|
|
|
for (uint16_t loc=0; loc<sizeof(_buffer); loc += LINUX_STORAGE_MAX_WRITE) {
|
|
|
|
if (write(fd, &_buffer[loc], LINUX_STORAGE_MAX_WRITE) != LINUX_STORAGE_MAX_WRITE) {
|
|
|
|
hal.scheduler->panic("Error filling FRAM");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// ensure the directory is updated with the new size
|
|
|
|
|
|
|
|
fsync(fd);
|
|
|
|
close(fd);
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage_FRAM::_storage_open(void)
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
|
|
|
if (_initialised) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
_dirty_mask = 0;
|
|
|
|
int fd = open();
|
|
|
|
if (fd == -1) {
|
|
|
|
_storage_create();
|
|
|
|
fd = open();
|
|
|
|
if (fd == -1) {
|
|
|
|
hal.scheduler->panic("Failed to access FRAM");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
|
|
|
_storage_create();
|
|
|
|
fd = open();
|
|
|
|
if (fd == -1) {
|
|
|
|
hal.scheduler->panic("Failed to access FRAM");
|
|
|
|
}
|
|
|
|
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
|
|
|
hal.scheduler->panic("Failed to read FRAM");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
_initialised = true;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage_FRAM::_timer_tick(void)
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
2014-08-25 13:18:48 -03:00
|
|
|
if (!_initialised || _dirty_mask == 0) {
|
2014-08-10 02:24:12 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2014-08-25 13:18:48 -03:00
|
|
|
if (_fd == -1) {
|
|
|
|
_fd = open();
|
|
|
|
if (_fd == -1) {
|
|
|
|
return;
|
|
|
|
}
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
|
2014-08-25 13:18:48 -03:00
|
|
|
// write out the first dirty set of lines. We don't write more
|
|
|
|
// than one to keep the latency of this call to a minimum
|
|
|
|
uint8_t i, n;
|
|
|
|
for (i=0; i<LINUX_STORAGE_NUM_LINES; i++) {
|
|
|
|
if (_dirty_mask & (1<<i)) {
|
|
|
|
break;
|
|
|
|
}
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
2014-08-25 13:18:48 -03:00
|
|
|
if (i == LINUX_STORAGE_NUM_LINES) {
|
|
|
|
// this shouldn't be possible
|
2014-08-10 02:24:12 -03:00
|
|
|
return;
|
|
|
|
}
|
2014-08-25 13:18:48 -03:00
|
|
|
uint32_t write_mask = (1U<<i);
|
|
|
|
// see how many lines to write
|
|
|
|
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
|
|
|
|
n < (LINUX_STORAGE_MAX_WRITE>>LINUX_STORAGE_LINE_SHIFT); n++) {
|
|
|
|
if (!(_dirty_mask & (1<<(n+i)))) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
// mark that line clean
|
|
|
|
write_mask |= (1<<(n+i));
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
|
2014-08-25 13:18:48 -03:00
|
|
|
/*
|
|
|
|
write the lines. This also updates _dirty_mask. Note that
|
|
|
|
because this is a SCHED_FIFO thread it will not be preempted
|
|
|
|
by the main task except during blocking calls. This means we
|
|
|
|
don't need a semaphore around the _dirty_mask updates.
|
|
|
|
*/
|
|
|
|
if (lseek(_fd, i<<LINUX_STORAGE_LINE_SHIFT, SEEK_SET) == (uint32_t)(i<<LINUX_STORAGE_LINE_SHIFT)) {
|
|
|
|
_dirty_mask &= ~write_mask;
|
|
|
|
if (write(_fd, &_buffer[i<<LINUX_STORAGE_LINE_SHIFT], n<<LINUX_STORAGE_LINE_SHIFT) != n<<LINUX_STORAGE_LINE_SHIFT) {
|
|
|
|
// write error - likely EINTR
|
|
|
|
_dirty_mask |= write_mask;
|
|
|
|
_fd = -1;
|
|
|
|
}
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
//File control function overloads
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int8_t Storage_FRAM::open()
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
|
|
|
if(_initialised){
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
uint8_t manufacturerID;
|
|
|
|
_spi = hal.spi->device(AP_HAL::SPIDevice_Dataflash);
|
|
|
|
uint8_t signature[4] = {0x00,0xaf,0xf0,0x0f};
|
|
|
|
uint8_t j = 0;
|
|
|
|
for(int i=0;true;i++){
|
|
|
|
manufacturerID = _register_read(0,OPCODE_RDID);
|
|
|
|
|
|
|
|
if(manufacturerID == 0x7F){
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
else{
|
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
}
|
|
|
|
if(i==4){
|
2015-10-24 18:45:41 -03:00
|
|
|
hal.scheduler->panic("FRAM: Failed to receive Manufacturer ID 5 times");
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
while(j<4){
|
|
|
|
if(_register_read(j+4100,OPCODE_READ) == -1){
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
else if((uint8_t)_register_read(j+4100,OPCODE_READ) != signature[j]){
|
|
|
|
while(_register_write(signature,4100,4) == -1);
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
else{
|
|
|
|
j++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
_initialised = true;
|
|
|
|
hal.console->println("FRAM: Online");
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int32_t Storage_FRAM::write(uint16_t fd,uint8_t *Buff, uint16_t NumBytes){
|
2014-08-25 13:18:48 -03:00
|
|
|
if( _register_write(Buff,fptr,NumBytes) == -1){
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
return NumBytes;
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
2015-10-20 18:13:25 -03:00
|
|
|
int32_t Storage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
2014-08-10 02:24:12 -03:00
|
|
|
for(uint16_t i=fptr;i<(fptr+NumBytes);i++){
|
|
|
|
Buff[i-fptr]= _register_read(i,OPCODE_READ);
|
|
|
|
|
2015-10-22 14:34:40 -03:00
|
|
|
if(Buff[i-fptr]==UINT8_MAX){
|
2014-08-25 13:18:48 -03:00
|
|
|
return -1;
|
|
|
|
}
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
fptr+=NumBytes;
|
|
|
|
return NumBytes;
|
|
|
|
}
|
2015-10-20 18:13:25 -03:00
|
|
|
uint32_t Storage_FRAM::lseek(uint16_t fd,uint32_t offset,uint16_t whence){
|
2014-08-10 02:24:12 -03:00
|
|
|
fptr = offset;
|
|
|
|
return offset;
|
|
|
|
}
|
|
|
|
|
|
|
|
//FRAM I/O functions
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int8_t Storage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t len ){
|
2014-08-10 02:24:12 -03:00
|
|
|
|
|
|
|
uint8_t *tx;
|
|
|
|
uint8_t *rx;
|
|
|
|
uint16_t i;
|
2014-08-25 13:18:48 -03:00
|
|
|
tx = new uint8_t[len+3];
|
|
|
|
rx = new uint8_t[len+3];
|
|
|
|
_write_enable(true);
|
2014-08-10 02:24:12 -03:00
|
|
|
|
|
|
|
tx[0] = OPCODE_WRITE;
|
|
|
|
tx[1] = addr>>8;
|
|
|
|
tx[2] = addr;
|
2014-08-25 13:18:48 -03:00
|
|
|
|
2014-08-10 02:24:12 -03:00
|
|
|
for(i=0;i<len;i++){
|
2014-08-25 13:18:48 -03:00
|
|
|
tx[i+3] = src[i];
|
|
|
|
}
|
|
|
|
if(transaction(tx, rx, len+3) == -1){
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
if(_write_enable(false) == -1){
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
return len;
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int8_t Storage_FRAM::_write_enable(bool enable)
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
|
|
|
uint8_t tx[2];
|
|
|
|
uint8_t rx[2];
|
2014-08-25 13:18:48 -03:00
|
|
|
if(enable){
|
|
|
|
tx[0] = OPCODE_WREN;
|
|
|
|
tx[1] = 0;
|
|
|
|
return transaction(tx, rx, 2);
|
|
|
|
}
|
|
|
|
else{
|
|
|
|
tx[0] = OPCODE_WRDI;
|
|
|
|
tx[1] = 0;
|
|
|
|
return transaction(tx, rx, 2);
|
|
|
|
}
|
|
|
|
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int8_t Storage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
|
2014-08-10 02:24:12 -03:00
|
|
|
{
|
2014-11-07 20:49:09 -04:00
|
|
|
uint8_t tx[4] = {opcode, (uint8_t)((addr >> 8U)), (uint8_t)(addr & 0xFF), 0};
|
2014-08-10 02:24:12 -03:00
|
|
|
uint8_t rx[4];
|
|
|
|
|
|
|
|
if(transaction(tx, rx, 4) == -1){
|
2014-08-25 13:18:48 -03:00
|
|
|
return -1;
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
return rx[3];
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
int8_t Storage_FRAM::transaction(uint8_t* tx, uint8_t* rx, uint16_t len){
|
2014-08-25 13:18:48 -03:00
|
|
|
_spi_sem = _spi->get_semaphore();
|
2014-08-10 02:24:12 -03:00
|
|
|
if (!_spi_sem->take(100)) {
|
|
|
|
// FRAM: Unable to get semaphore
|
2014-08-25 13:18:48 -03:00
|
|
|
return -1;
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
_spi->transaction(tx, rx, len);
|
2014-08-25 13:18:48 -03:00
|
|
|
_spi_sem->give();
|
|
|
|
return 0;
|
2014-08-10 02:24:12 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|