mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL_Linux: remove unused Dataflash
This is selectable by a define and is never changed. Just remove everything referencing it: we can come up with a better solution if it is actually used later.
This commit is contained in:
parent
f936291a52
commit
8681d23cbd
@ -13,7 +13,6 @@ namespace Linux {
|
||||
class GPIO_RPI;
|
||||
class GPIO_Sysfs;
|
||||
class Storage;
|
||||
class Storage_FRAM;
|
||||
class DigitalSource;
|
||||
class DigitalSource_Sysfs;
|
||||
class PeriodicThread;
|
||||
|
@ -64,14 +64,7 @@ static AnalogIn_Navio2 analogIn;
|
||||
static Empty::AnalogIn analogIn;
|
||||
#endif
|
||||
|
||||
/*
|
||||
select between FRAM and FS
|
||||
*/
|
||||
#if LINUX_STORAGE_USE_FRAM == 1
|
||||
static Storage_FRAM storageDriver;
|
||||
#else
|
||||
static Storage storageDriver;
|
||||
#endif
|
||||
|
||||
/*
|
||||
use the BBB gpio driver on ERLE, PXF and BBBMINI
|
||||
|
@ -31,7 +31,6 @@ SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver("mpu6000", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_28, 500*1000, 20*MHZ),
|
||||
/* MPU9250 is restricted to 1MHz for non-data and interrupt registers */
|
||||
SPIDeviceDriver("mpu9250", 2, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, BBB_P9_23, 1*MHZ, 20*MHZ),
|
||||
SPIDeviceDriver("dataflash", 2, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, BBB_P8_12, 6*MHZ, 6*MHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
||||
SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
@ -67,7 +66,6 @@ SPIDeviceDriver SPIDeviceManager::_device[] = {
|
||||
SPIDeviceDriver("ms5611", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_23, 10*MHZ, 10*MHZ),
|
||||
SPIDeviceDriver("lsm9ds0_am", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_22, 10*MHZ, 10*MHZ),
|
||||
SPIDeviceDriver("lsm9ds0_g", 0, 0, AP_HAL::SPIDevice_Type, SPI_MODE_3, 8, RPI_GPIO_12, 10*MHZ, 10*MHZ),
|
||||
SPIDeviceDriver("dataflash", 0, 0, AP_HAL::SPIDevice_Dataflash, SPI_MODE_3, 8, RPI_GPIO_5, 6*MHZ, 6*MHZ),
|
||||
SPIDeviceDriver("raspio", 0, 0, AP_HAL::SPIDevice_RASPIO, SPI_MODE_3, 8, RPI_GPIO_7, 10*MHZ, 10*MHZ),
|
||||
};
|
||||
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
|
||||
|
@ -1,7 +1,5 @@
|
||||
#pragma once
|
||||
|
||||
#define LINUX_STORAGE_USE_FRAM 0
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
@ -41,5 +39,3 @@ protected:
|
||||
uint8_t _buffer[LINUX_STORAGE_SIZE];
|
||||
volatile uint32_t _dirty_mask;
|
||||
};
|
||||
|
||||
#include "Storage_FRAM.h"
|
||||
|
@ -1,260 +0,0 @@
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <inttypes.h>
|
||||
#include <stdio.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/types.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "Storage.h"
|
||||
|
||||
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;
|
||||
Storage_FRAM::Storage_FRAM():
|
||||
_spi(NULL),
|
||||
_spi_sem(NULL)
|
||||
{}
|
||||
|
||||
void Storage_FRAM::_storage_create(void)
|
||||
{
|
||||
|
||||
int fd = open();
|
||||
hal.console->println("Storage: FRAM is getting reset to default values");
|
||||
|
||||
if (fd == -1) {
|
||||
AP_HAL::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) {
|
||||
AP_HAL::panic("Error filling FRAM");
|
||||
}
|
||||
}
|
||||
|
||||
// ensure the directory is updated with the new size
|
||||
|
||||
fsync(fd);
|
||||
close(fd);
|
||||
}
|
||||
|
||||
void Storage_FRAM::_storage_open(void)
|
||||
{
|
||||
if (_initialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
_dirty_mask = 0;
|
||||
int fd = open();
|
||||
if (fd == -1) {
|
||||
_storage_create();
|
||||
fd = open();
|
||||
if (fd == -1) {
|
||||
AP_HAL::panic("Failed to access FRAM");
|
||||
}
|
||||
}
|
||||
|
||||
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
||||
_storage_create();
|
||||
fd = open();
|
||||
if (fd == -1) {
|
||||
AP_HAL::panic("Failed to access FRAM");
|
||||
}
|
||||
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
||||
AP_HAL::panic("Failed to read FRAM");
|
||||
}
|
||||
}
|
||||
_initialised = true;
|
||||
}
|
||||
|
||||
void Storage_FRAM::_timer_tick(void)
|
||||
{
|
||||
if (!_initialised || _dirty_mask == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (_fd == -1) {
|
||||
_fd = open();
|
||||
if (_fd == -1) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// 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;
|
||||
}
|
||||
}
|
||||
if (i == LINUX_STORAGE_NUM_LINES) {
|
||||
// this shouldn't be possible
|
||||
return;
|
||||
}
|
||||
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));
|
||||
}
|
||||
|
||||
/*
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
//File control function overloads
|
||||
|
||||
int8_t Storage_FRAM::open()
|
||||
{
|
||||
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){
|
||||
AP_HAL::panic("FRAM: Failed to receive Manufacturer ID 5 times");
|
||||
}
|
||||
}
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
int32_t Storage_FRAM::write(uint16_t fd,uint8_t *Buff, uint16_t NumBytes){
|
||||
if( _register_write(Buff,fptr,NumBytes) == -1){
|
||||
return -1;
|
||||
}
|
||||
return NumBytes;
|
||||
}
|
||||
int32_t Storage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
||||
for(uint16_t i=fptr;i<(fptr+NumBytes);i++){
|
||||
Buff[i-fptr]= _register_read(i,OPCODE_READ);
|
||||
|
||||
if(Buff[i-fptr]==UINT8_MAX){
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
fptr+=NumBytes;
|
||||
return NumBytes;
|
||||
}
|
||||
uint32_t Storage_FRAM::lseek(uint16_t fd,uint32_t offset,uint16_t whence){
|
||||
fptr = offset;
|
||||
return offset;
|
||||
}
|
||||
|
||||
//FRAM I/O functions
|
||||
|
||||
int8_t Storage_FRAM::_register_write( uint8_t* src, uint16_t addr, uint16_t len ){
|
||||
|
||||
uint8_t *tx;
|
||||
uint8_t *rx;
|
||||
uint16_t i;
|
||||
tx = new uint8_t[len+3];
|
||||
rx = new uint8_t[len+3];
|
||||
_write_enable(true);
|
||||
|
||||
tx[0] = OPCODE_WRITE;
|
||||
tx[1] = addr>>8;
|
||||
tx[2] = addr;
|
||||
|
||||
for(i=0;i<len;i++){
|
||||
tx[i+3] = src[i];
|
||||
}
|
||||
if(transaction(tx, rx, len+3) == -1){
|
||||
return -1;
|
||||
}
|
||||
if(_write_enable(false) == -1){
|
||||
return -1;
|
||||
}
|
||||
return len;
|
||||
}
|
||||
|
||||
int8_t Storage_FRAM::_write_enable(bool enable)
|
||||
{
|
||||
uint8_t tx[2];
|
||||
uint8_t rx[2];
|
||||
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);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int8_t Storage_FRAM::_register_read( uint16_t addr, uint8_t opcode )
|
||||
{
|
||||
uint8_t tx[4] = {opcode, (uint8_t)((addr >> 8U)), (uint8_t)(addr & 0xFF), 0};
|
||||
uint8_t rx[4];
|
||||
|
||||
if(transaction(tx, rx, 4) == -1){
|
||||
return -1;
|
||||
}
|
||||
return rx[3];
|
||||
}
|
||||
|
||||
int8_t Storage_FRAM::transaction(uint8_t* tx, uint8_t* rx, uint16_t len){
|
||||
_spi_sem = _spi->get_semaphore();
|
||||
if (!_spi_sem->take(100)) {
|
||||
// FRAM: Unable to get semaphore
|
||||
return -1;
|
||||
}
|
||||
_spi->transaction(tx, rx, len);
|
||||
_spi_sem->give();
|
||||
return 0;
|
||||
}
|
@ -1,38 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_Linux_Namespace.h"
|
||||
|
||||
#define OPCODE_WREN 0b0110 /* Write Enable Latch */
|
||||
#define OPCODE_WRDI 0b0100 /* Reset Write Enable Latch */
|
||||
#define OPCODE_RDSR 0b0101 /* Read Status Register */
|
||||
#define OPCODE_WRSR 0b0001 /* Write Status Register */
|
||||
#define OPCODE_READ 0b0011 /* Read Memory */
|
||||
#define OPCODE_WRITE 0b0010 /* Write Memory */
|
||||
#define OPCODE_RDID 0b10011111 /* Read Device ID */
|
||||
|
||||
class Linux::Storage_FRAM : public Linux::Storage
|
||||
{
|
||||
public:
|
||||
Storage_FRAM();
|
||||
void _timer_tick(void);
|
||||
|
||||
private:
|
||||
uint32_t fptr;
|
||||
|
||||
int32_t write(uint16_t fd, uint8_t *Buff, uint16_t NumBytes);
|
||||
int32_t read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes);
|
||||
uint32_t lseek(uint16_t fd,uint32_t offset,uint16_t whence);
|
||||
int8_t open();
|
||||
|
||||
int8_t _register_write( uint8_t* src, uint16_t addr, uint16_t len );
|
||||
int8_t _register_read( uint16_t addr, uint8_t opcode );
|
||||
int8_t _write_enable(bool enable);
|
||||
int8_t transaction(uint8_t* tx, uint8_t* rx, uint16_t len);
|
||||
|
||||
void _storage_create(void);
|
||||
void _storage_open(void);
|
||||
|
||||
AP_HAL::SPIDeviceDriver *_spi;
|
||||
AP_HAL::Semaphore *_spi_sem;
|
||||
};
|
Loading…
Reference in New Issue
Block a user