Merge pull request #164 from Telecominfraproject/FW_SPI_filesys

code changes for SPI filesystem
This commit is contained in:
Joshua Jeyaraj
2018-11-05 13:25:36 +05:30
committed by GitHub
21 changed files with 3922 additions and 10 deletions

View File

@@ -574,10 +574,11 @@ m3Hwi1Params.instance.name = "m3Hwi1";
Program.global.m3Hwi1 = m3Hwi.create(60, "&uDMAIntHandler", m3Hwi1Params);
*/
var m3Hwi2Params = new m3Hwi.Params();
/*Below configuration has some conflict with SPI DMA, doesn't work with it */
/*var m3Hwi2Params = new m3Hwi.Params();
m3Hwi2Params.instance.name = "m3Hwi2";
m3Hwi2Params.enableInt = false;
Program.global.m3Hwi2 = m3Hwi.create(61, "&uDMAErrorHandler", m3Hwi2Params);
Program.global.m3Hwi2 = m3Hwi.create(61, "&uDMAErrorHandler", m3Hwi2Params);*/
/* ================ Application Specific Instances ================ */
/* ================ NDK configuration ================ */

View File

@@ -204,6 +204,16 @@ typedef enum OC_CONNECT1_I2CName {
OC_CONNECT1_I2CCOUNT
} OC_CONNECT1_I2CName;
/*!
* @def DK_TM4C129X_SPIName
* @brief Enum of SPI names on the DK_TM4C129X dev board
*/
typedef enum DK_TM4C129X_SPIName {
OC_CONNECT1_SPI0 = 0,
OC_CONNECT1_SPICOUNT
} OC_CONNECT1_SPIName;
/*!
* @def OC_CONNECT1_debugMdioName
* @brief Enum of debug MDIO names for Ethernet components

View File

@@ -0,0 +1,19 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*/
#ifndef COMMON_INC_OCMP_WRAPPERS_OCMP_FLASH_H_
#define COMMON_INC_OCMP_WRAPPERS_OCMP_FLASH_H_
#define FRAME_SIZE 64
#define LAST_MSG_FLAG 0
#define NEXT_MSG_FLAG_POS 17
#define NEXT_MSG_FLAG 1
#define PAYLOAD_SIZE 47
#endif /* COMMON_INC_OCMP_WRAPPERS_OCMP_FLASH_H_ */

View File

@@ -13,6 +13,7 @@
SCHEMA_IMPORT bool SYS_post_get_results(void **getpostResult);
SCHEMA_IMPORT bool SYS_post_enable(void **postActivate);
SCHEMA_IMPORT const Driver_fxnTable AT45DB641E_fxnTable;
SCHEMA_IMPORT const Driver_fxnTable CAT24C04_gbc_sid_fxnTable;
SCHEMA_IMPORT const Driver_fxnTable CAT24C04_gbc_inv_fxnTable;
SCHEMA_IMPORT const Driver_fxnTable CAT24C04_sdr_inv_fxnTable;
@@ -75,4 +76,9 @@ static const Driver SYSTEMDRV = {
}
};
static const Driver FLASHDRV = {
.name = "FLASHDRV",
.fxnTable = &AT45DB641E_fxnTable,
};
#endif /* INC_DEVICES_OCMP_EEPROM_H_ */

View File

@@ -0,0 +1,50 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*/
#ifndef INC_COMMON_SPIBUS_H_
#define INC_COMMON_SPIBUS_H_
/*****************************************************************************
* HEADER FILES
*****************************************************************************/
#include "drivers/OcGpio.h"
#include "inc/common/global_header.h"
#include <stdint.h>
#include <stdbool.h>
#include <ti/drivers/SPI.h>
#include <ti/sysbios/gates/GateMutex.h>
typedef struct SPI_Dev {
unsigned int bus;
OcGpio_Pin *chip_select;
} SPI_Dev;
/*****************************************************************************
* FUNCTION DECLARATIONS
*****************************************************************************/
SPI_Handle spi_get_handle(unsigned int index);
ReturnStatus spi_reg_read(SPI_Handle spiHandle,
OcGpio_Pin *chip_select,
void *regAddress,
uint8_t *data,
uint32_t data_size,
uint32_t byte,
uint8_t numofBytes);
ReturnStatus spi_reg_write(SPI_Handle spiHandle,
OcGpio_Pin *chip_select,
void *regAddress,
uint8_t *data,
uint32_t data_size,
uint32_t byte,
uint8_t numofBytes);
#endif /* INC_COMMON_SPIBUS_H_ */

View File

@@ -0,0 +1,52 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
*/
#ifndef INC_DEVICES_AT45DB_H_
#define INC_DEVICES_AT45DB_H_
#include "common/inc/global/post_frame.h"
#include "drivers/OcGpio.h"
#include "inc/common/spibus.h"
#include "inc/common/global_header.h"
/*****************************************************************************
* STRUCT/ENUM DEFINITIONS
*****************************************************************************/
typedef enum AT45DB_Event {
AT45DB_READ_EVENT = 0,
} AT45DB_Event;
typedef void (*AT45DB_CallbackFn) (AT45DB_Event evt, uint16_t value,
void *context);
typedef struct AT45DB_Cfg {
SPI_Dev dev;
OcGpio_Pin *pin_alert;
} AT45DB_Cfg;
typedef struct AT45DB_Obj {
AT45DB_CallbackFn alert_cb;
void *cb_context;
AT45DB_Event evt_to_monitor;
} AT45DB_Obj;
typedef struct AT45DB_Dev {
const AT45DB_Cfg cfg;
AT45DB_Obj obj;
} AT45DB_Dev;
ePostCode at45db_probe(AT45DB_Dev *dev, POSTData *postData);
ReturnStatus at45db_data_read(AT45DB_Dev *dev, uint8_t *data, uint32_t data_size, uint32_t byte, uint32_t page);
ReturnStatus at45db_data_write(AT45DB_Dev *dev, uint8_t *data, uint32_t data_size, uint32_t byte, uint32_t page);
ReturnStatus at45db_erasePage(AT45DB_Dev *dev, uint32_t page);
uint8_t at45db_readStatusRegister(AT45DB_Dev *dev);
#endif /* INC_DEVICES_AT45DB_H_ */

View File

@@ -278,6 +278,8 @@ extern GPIO_PinConfig gpioPinConfigs[];
GPIO_PinConfig gpioPinConfigs[OC_EC_GPIOCOUNT] = {
[OC_EC_SOC_UART3_TX] =
GPIOTiva_PA_5 | GPIO_CFG_IN_NOPULL | GPIO_CFG_IN_INT_BOTH_EDGES,
[OC_EC_FLASH_nCS] =
GPIOTiva_PB_4 | GPIO_CFG_OUT_STD | GPIO_CFG_OUT_STR_HIGH | GPIO_CFG_OUT_HIGH,
[OC_EC_SDR_INA_ALERT] =
GPIOTiva_PD_2 | GPIO_CFG_IN_NOPULL | GPIO_CFG_IN_INT_FALLING,
[OC_EC_PWR_PSE_RESET] =
@@ -686,6 +688,70 @@ void OC_CONNECT1_initI2C(void)
I2C_init();
}
/*
* =============================== SPI ===============================
*/
/* Place into subsections to allow the TI linker to remove items properly */
#if defined(__TI_COMPILER_VERSION__)
#pragma DATA_SECTION(SPI_config, ".const:SPI_config")
#pragma DATA_SECTION(spiTivaDMAHWAttrs, ".const:spiTivaDMAHWAttrs")
#endif
#include <ti/drivers/SPI.h>
#include <ti/drivers/spi/SPITivaDMA.h>
SPITivaDMA_Object spiTivaDMAObjects[OC_CONNECT1_SPICOUNT];
#if defined(__TI_COMPILER_VERSION__)
#pragma DATA_ALIGN(spiTivaDMAscratchBuf, 32)
#elif defined(__IAR_SYSTEMS_ICC__)
#pragma data_alignment=32
#elif defined(__GNUC__)
__attribute__ ((aligned (32)))
#endif
uint32_t spiTivaDMAscratchBuf[OC_CONNECT1_SPICOUNT];
const SPITivaDMA_HWAttrs spiTivaDMAHWAttrs[OC_CONNECT1_SPICOUNT] = {
{
.baseAddr = SSI1_BASE,
.intNum = INT_SSI1,
.intPriority = (~0),
.scratchBufPtr = &spiTivaDMAscratchBuf[0],
.defaultTxBufValue = 0,
.rxChannelIndex = UDMA_CHANNEL_SSI1RX,
.txChannelIndex = UDMA_CHANNEL_SSI1TX,
.channelMappingFxn = uDMAChannelAssign,
.rxChannelMappingFxnArg = UDMA_CH24_SSI1RX,
.txChannelMappingFxnArg = UDMA_CH25_SSI1TX
},
};
const SPI_Config SPI_config[] = {
[OC_CONNECT1_SPI0] = {
.fxnTablePtr = &SPITivaDMA_fxnTable,
.object = &spiTivaDMAObjects[OC_CONNECT1_SPI0],
.hwAttrs = &spiTivaDMAHWAttrs[OC_CONNECT1_SPI0]
},
{NULL, NULL, NULL},
};
/*
* ======== OC_CONNECT1_initSPI ========
*/
void OC_CONNECT1_initSPI(void)
{
SysCtlPeripheralEnable(SYSCTL_PERIPH_SSI1);
GPIOPinConfigure(GPIO_PB5_SSI1CLK);
GPIOPinConfigure(GPIO_PB4_SSI1FSS);
GPIOPinConfigure(GPIO_PE4_SSI1XDAT0);
GPIOPinConfigure(GPIO_PE5_SSI1XDAT1);
GPIOPinTypeSSI(GPIO_PORTB_BASE, GPIO_PIN_4 | GPIO_PIN_5);
GPIOPinTypeSSI(GPIO_PORTE_BASE, GPIO_PIN_4 | GPIO_PIN_5);
OC_CONNECT1_initDMA();
SPI_init();
}
/*
* =============================== UART ===============================
*/
@@ -965,4 +1031,4 @@ void OC_CONNECT1_initWatchdog(void)
SysCtlPeripheralEnable(SYSCTL_PERIPH_WDOG0);
Watchdog_init();
}
}

View File

@@ -25,6 +25,8 @@
#include "inc/subsystem/power/power.h"
#include "inc/devices/eth_sw.h"
#include "inc/devices/eeprom.h"
#include "inc/common/spibus.h"
#include "inc/devices/at45db.h"
#include <stdint.h>
#include <stdbool.h>
@@ -63,6 +65,17 @@ Eeprom_Cfg eeprom_gbc_inv = {
/*****************************************************************************
* SYSTEM CONFIG
*****************************************************************************/
/* SPI AT45DB Flash Config */
AT45DB_Dev gbc_spi_flash_memory = {
.cfg = {
.dev = {
.bus = OC_CONNECT1_SPI0,
.chip_select = &(OcGpio_Pin){ &ec_io, OC_EC_FLASH_nCS },
},
.pin_alert = NULL,
},
.obj = {},
};
/* Power SubSystem Config */
//Lead Acid Temperature sensor.
SE98A_Dev gbc_pwr_lead_acid_ts = {
@@ -565,4 +578,4 @@ const INA226_Config fact_ap_3v_ps_cfg = {
const INA226_Config fact_msata_3v_ps_cfg = {
.current_lim = 1500,
};
};

View File

@@ -38,6 +38,7 @@ SCHEMA_IMPORT DriverStruct eeprom_gbc_sid;
SCHEMA_IMPORT DriverStruct eeprom_gbc_inv;
SCHEMA_IMPORT DriverStruct eeprom_sdr_inv;
SCHEMA_IMPORT DriverStruct eeprom_fe_inv;
SCHEMA_IMPORT DriverStruct gbc_spi_flash_memory;
/* Power SubSystem Configs */
SCHEMA_IMPORT DriverStruct gbc_pwr_lead_acid_ts;
SCHEMA_IMPORT DriverStruct gbc_pwr_ext_bat_charger;
@@ -214,6 +215,7 @@ SCHEMA_IMPORT bool SYNC_Init(void *driver, void *returnValue);
SCHEMA_IMPORT bool SYNC_reset(void *driver, void *params);
SCHEMA_IMPORT bool SYS_cmdReset(void *driver, void *params);
SCHEMA_IMPORT bool SYS_cmdEcho(void *driver, void *params);
SCHEMA_IMPORT bool sys_post_init(void* driver, void *returnValue);
SCHEMA_IMPORT bool TestMod_cmdEnable(void *driver, void *params);
SCHEMA_IMPORT bool TestMod_cmdDisable(void *driver, void *params);
SCHEMA_IMPORT bool TestMod_cmdDisconnect(void *driver, void *params);
@@ -250,6 +252,11 @@ const Component sys_schema[] = {
.name = "eeprom_mac",
.driver = &Driver_MAC,
},
{
.name = "SPI_flash",
.driver = &FLASHDRV,
.driver_cfg = &gbc_spi_flash_memory,
},
{}
},
.commands = (Command[]){
@@ -266,6 +273,10 @@ const Component sys_schema[] = {
},
{}
},
.driver_cfg = &gbc_spi_flash_memory,
.ssHookSet = &(SSHookSet) {
.postInitFxn = (ssHook_Cb)sys_post_init,
},
},
{
.name = "power",

View File

@@ -48,6 +48,7 @@ extern "C" {
#define Board_initGeneral OC_CONNECT1_initGeneral
#define Board_initGPIO OC_CONNECT1_initGPIO
#define Board_initI2C OC_CONNECT1_initI2C
#define Board_initSPI OC_CONNECT1_initSPI
#define Board_initUART OC_CONNECT1_initUART
#define Board_initUSB OC_CONNECT1_initUSB
#define Board_initWatchdog OC_CONNECT1_initWatchdog

View File

@@ -0,0 +1,283 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
* This file is used as Device layer for AT45DB641E. Mainly it contains Data read,
* Data write, Page erase, Status check functions, these functions are called by
* littlefs filesystyem in order to perform read/write operation for data using SPI
* interface. Also while post execution device and manufacturing id's of AT45DB641E
* will be verified by probe function.
*/
#include "inc/devices/at45db.h"
#include "inc/common/spibus.h"
#include "inc/common/global_header.h"
#include "inc/global/OC_CONNECT1.h"
#define AT45DB_DATA_WR_OPCODE_WR_COUNT 4
#define AT45DB_DATA_RD_OPCODE_WR_COUNT 8
#define AT45DB_DEVICE_ID 0x0028
#define AT45DB_DEVID_RD_BYTES 2
#define AT45DB_DEVID_RD_OPCODE 0x9F
#define AT45DB_DEVID_OPCODE_WR_COUNT 1
#define AT45DB_ERASE_OPCODE_WR_COUNT 4
#define AT45DB_MANFACTURE_ID 0x1F
#define AT45DB_PAGE_ERASE_OPCODE 0x81
#define AT45DB_PAGE_RD_OPCODE 0xD2
#define AT45DB_PAGE_WR_OPCODE 0x86
#define AT45DB_READY 0x80 /* AT45DB Ready Value */
#define AT45DB_SRAM_BUFF2_WR_OPCODE 0x87
#define AT45DB_STATUS_OPCODE 0xD7
#define AT45DB_STATUS_OPCODE_WR_COUNT 1
#define AT45DB_STATUS_RD_BYTES 1
#define waitForReady(dev) \
while (!(AT45DB_READY & at45db_readStatusRegister(dev)));
/*****************************************************************************
** FUNCTION NAME : AT45DB_read_reg
**
** DESCRIPTION : Reads 8 bit values from at45db page or register.
**
** ARGUMENTS : spi device configuration, cmd buffer, register value,
** page offset, numOfBytes to be read, cmd write count.
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
static ReturnStatus AT45DB_read_reg(AT45DB_Dev *dev,
void *cmdbuffer, /* cmd or opcode buffer */
uint8_t *regValue,
uint32_t pageOffset,
uint32_t NumOfbytes,
uint8_t writeCount)
{
ReturnStatus status = RETURN_NOTOK;
SPI_Handle at45dbHandle = spi_get_handle(dev->cfg.dev.bus);
if (!at45dbHandle) {
LOGGER_ERROR("AT45DBFLASHMEMORY:ERROR:: Failed to get SPI Bus for at45db flash memory "
"0x%x on bus 0x%x.\n", dev->cfg.dev.chip_select,
dev->cfg.dev.bus);
} else {
status = spi_reg_read(at45dbHandle,
dev->cfg.dev.chip_select,
cmdbuffer,
regValue,
NumOfbytes,
pageOffset,
writeCount);
}
return status;
}
/*****************************************************************************
** FUNCTION NAME : AT45DB_write_reg
**
** DESCRIPTION : Write 8 bit value to at45db page or register.
**
** ARGUMENTS : spi device configuration, cmd buffer, register value,
** page offset, numOfBytes to be written, cmd write count.
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
static ReturnStatus AT45DB_write_reg(AT45DB_Dev *dev,
void *cmdbuffer, /* cmd or opcode buffer */
uint8_t *regValue,
uint32_t pageOffset,
uint32_t NumOfbytes,
uint8_t writeCount)
{
ReturnStatus status = RETURN_NOTOK;
SPI_Handle at45dbHandle = spi_get_handle(dev->cfg.dev.bus);
if (!at45dbHandle) {
LOGGER_ERROR("AT45DBFLASHMEMORY:ERROR:: Failed to get SPI Bus for at45db flash memory "
"0x%x on bus 0x%x.\n", dev->cfg.dev.chip_select,
dev->cfg.dev.bus);
} else {
status = spi_reg_write(at45dbHandle,
dev->cfg.dev.chip_select,
cmdbuffer,
regValue,
NumOfbytes,
pageOffset,
writeCount);
}
return status;
}
/*****************************************************************************
** FUNCTION NAME : at45db_readStatusRegister
**
** DESCRIPTION : Reads status of at45db device whether it is ready for
**
** r/w operation
**
** ARGUMENTS : spi device configuration
**
** RETURN TYPE : 8-bit status code
**
*****************************************************************************/
uint8_t at45db_readStatusRegister(AT45DB_Dev *dev)
{
uint8_t txBuffer = AT45DB_STATUS_OPCODE; /* opcode for ready status of AT45DB */;
uint8_t status;
AT45DB_read_reg(dev, &txBuffer, &status, NULL, AT45DB_STATUS_RD_BYTES, AT45DB_STATUS_OPCODE_WR_COUNT);
return (status);
}
/*****************************************************************************
** FUNCTION NAME : at45db_erasePage
**
** DESCRIPTION : Erases at45db memory page before writing data to it
**
** ARGUMENTS : spi device configuration, page number to be erased
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
ReturnStatus at45db_erasePage(AT45DB_Dev *dev, uint32_t page)
{
ReturnStatus status = RETURN_NOTOK;
uint8_t txBuffer[4];
waitForReady(dev);
txBuffer[0] = AT45DB_PAGE_ERASE_OPCODE; /* opcode to erase main memory page */
txBuffer[1] = (uint8_t)(page >> 7); /* Page size is 15 bits 8 in tx1 and 7 in tx2 */
txBuffer[2] = (uint8_t)(page << 1);
txBuffer[3] = 0x00;
status = AT45DB_write_reg(dev, txBuffer, NULL, NULL, NULL, AT45DB_ERASE_OPCODE_WR_COUNT);
return status;
}
/*****************************************************************************
** FUNCTION NAME : at45db_data_read
**
** DESCRIPTION : Reads data from at45db memory page
**
** ARGUMENTS : spi device configuration, data pointer, data size,
**
** page offset, page number
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
ReturnStatus at45db_data_read(AT45DB_Dev *dev, uint8_t *data, uint32_t data_size, uint32_t byte, uint32_t page)
{
ReturnStatus status = RETURN_NOTOK;
uint8_t txBuffer[8]; /* last 4 bytes are needed, but have don't care values */
waitForReady(dev);
txBuffer[0] = AT45DB_PAGE_RD_OPCODE; /* opcode to read main memory page */
txBuffer[1] = (uint8_t)(page >> 7); /* Page size is 15 bits 8 in tx1 and 7 in tx2 */
txBuffer[2] = (uint8_t)((page << 1));
txBuffer[3] = (uint8_t)(0xFF & byte);
status = AT45DB_read_reg(dev, &txBuffer, data, byte, data_size, AT45DB_DATA_RD_OPCODE_WR_COUNT);
return status;
}
/*****************************************************************************
** FUNCTION NAME : at45db_data_write
**
** DESCRIPTION : Writes data to at45db memory page
**
** ARGUMENTS : spi device configuration, data pointer, data size,
**
** page offset, page number
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
ReturnStatus at45db_data_write(AT45DB_Dev *dev, uint8_t *data, uint32_t data_size, uint32_t byte, uint32_t page)
{
ReturnStatus status = RETURN_NOTOK;
uint8_t txBuffer[4];
waitForReady(dev);
txBuffer[0] = AT45DB_SRAM_BUFF2_WR_OPCODE; /* opcode to write data to AT45DB SRAM Buffer2 */
txBuffer[1] = 0x00;
txBuffer[2] = (uint8_t)(0x1 & (byte >> 8)); /* 9 bit buffer address */
txBuffer[3] = (uint8_t)(0xFF & byte);
status = AT45DB_write_reg(dev, &txBuffer, data, byte, data_size, AT45DB_DATA_WR_OPCODE_WR_COUNT);
if(status == RETURN_OK) {
waitForReady(dev);
txBuffer[0] = AT45DB_PAGE_WR_OPCODE; /* opcode to Push the data from AT45DB SRAM Buffer2 to the page */
txBuffer[1] = (uint8_t)(page >> 7); /* Page size is 15 bits 8 in tx1 and 7 in tx2 */
txBuffer[2] = (uint8_t)(page << 1);
txBuffer[3] = 0x00;
status = AT45DB_write_reg(dev, &txBuffer, data, byte, data_size, AT45DB_DATA_WR_OPCODE_WR_COUNT);
}
return status;
}
/*****************************************************************************
** FUNCTION NAME : at45db_getDevID
**
** DESCRIPTION : Reads Device id and manufacturing id of at45db device
**
** ARGUMENTS : spi device configuration, data pointer
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
static ReturnStatus at45db_getDevID(AT45DB_Dev *dev, uint32_t *devID)
{
uint8_t txBuffer = AT45DB_DEVID_RD_OPCODE; /* opcode to get device id */
return AT45DB_read_reg(dev, &txBuffer, devID, NULL, AT45DB_DEVID_RD_BYTES, AT45DB_DEVID_OPCODE_WR_COUNT);
}
/*****************************************************************************
** FUNCTION NAME : at45db_probe
**
** DESCRIPTION : Compares device and manufacturing id's for post
**
** ARGUMENTS : spi device configuration, post data pointer
**
** RETURN TYPE : ePostCode type status, can be found in post_frame.h
**
*****************************************************************************/
ePostCode at45db_probe(AT45DB_Dev *dev, POSTData *postData)
{
uint32_t value = 0;
uint16_t devId = 0;
uint8_t manfId = 0;
if (at45db_getDevID(dev, &value) != RETURN_OK) {
return POST_DEV_MISSING;
}
devId = (value >> 8) & 0xFFFF;
if (devId != AT45DB_DEVICE_ID) {
return POST_DEV_ID_MISMATCH;
}
manfId = value & 0xFF;
if (manfId != AT45DB_MANFACTURE_ID) {
return POST_DEV_ID_MISMATCH;
}
post_update_POSTData(postData, dev->cfg.dev.bus, NULL,manfId, devId);
return POST_DEV_FOUND;
}

View File

@@ -0,0 +1,36 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
* This is wrapper file for at45db device contains wrapper functions like probe
* and function table of it. probe function calls device layer functions to
* complete post execution
*/
#include "common/inc/global/Framework.h"
#include "common/inc/ocmp_wrappers/ocmp_at45db.h"
#include "inc/devices/at45db.h"
/*****************************************************************************
** FUNCTION NAME : _probe
**
** DESCRIPTION : Wrapper function for post execution
**
** ARGUMENTS : spi device configuration, post data pointer
**
** RETURN TYPE : ePostCode type status, can be found in post_frame.h
**
*****************************************************************************/
static ePostCode _probe(void *driver, POSTData *postData)
{
return at45db_probe(driver,postData);
}
const Driver_fxnTable AT45DB641E_fxnTable = {
/* Message handlers */
.cb_probe = _probe,
};

View File

@@ -0,0 +1,167 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
* This file contains SPI driver's API within spi_get_handle, spi_reg_read and
* spi_reg_write which ccan be called by device layer to communicate any SPI device.
*/
//*****************************************************************************
// HANDLES DEFINITION
//*****************************************************************************
#include "Board.h"
#include "drivers/OcGpio.h"
#include "inc/common/spibus.h"
#include "inc/global/OC_CONNECT1.h"
#include <ti/drivers/GPIO.h>
#include <ti/drivers/SPI.h>
#include <ti/sysbios/BIOS.h>
#include <ti/sysbios/gates/GateMutex.h>
#include <ti/sysbios/knl/Queue.h>
#include <ti/sysbios/knl/Semaphore.h>
#include <ti/sysbios/knl/Task.h>
#include <xdc/std.h>
#include <xdc/cfg/global.h>
#include <xdc/runtime/System.h>
#include <xdc/runtime/Memory.h>
#define PIN_LOW (0)
#define PIN_HIGH ~(0)
/*****************************************************************************
** FUNCTION NAME : spi_get_handle
**
** DESCRIPTION : Initialize SPI Bus
**
** ARGUMENTS : SPI bus index
**
** RETURN TYPE : SPI_Handle (NULL on failure)
**
*****************************************************************************/
SPI_Handle spi_get_handle(uint32_t index) {
SPI_Params spiParams;
SPI_Handle spiHandle;
SPI_Params_init(&spiParams);
spiHandle = SPI_open(index, &spiParams);
if (spiHandle == NULL) {
LOGGER_ERROR("SPI_open failed\n");
return false;
}
return spiHandle;
}
/*****************************************************************************
** FUNCTION NAME : spi_reg_read
**
** DESCRIPTION : Writing device register over SPI bus.
**
** ARGUMENTS : SPI handle, chip select, register address, data, data
**
** length, offset byte, numOfBytes for cmd write count
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
ReturnStatus spi_reg_read(SPI_Handle spiHandle,
OcGpio_Pin *chip_select,
void *regAddress,
uint8_t *data,
uint32_t data_size,
uint32_t byte,
uint8_t numofBytes)
{
ReturnStatus status = RETURN_OK;
SPI_Transaction spiTransaction;
spiTransaction.count = numofBytes; /* Initialize master SPI transaction structure */
spiTransaction.txBuf = regAddress;
spiTransaction.rxBuf = NULL;
OcGpio_write(chip_select, PIN_LOW);/* Initiate SPI transfer */
if (SPI_transfer(spiHandle, &spiTransaction)) {
status = RETURN_OK;
} else {
LOGGER_ERROR("SPIBUS:ERROR:: SPI write failed");
status = RETURN_NOTOK;
}
spiTransaction.count = data_size;
spiTransaction.txBuf = NULL;
spiTransaction.rxBuf = data;
if (SPI_transfer(spiHandle, &spiTransaction)) {
status = RETURN_OK;
} else {
LOGGER_ERROR("SPIBUS:ERROR:: SPI read failed");
status = RETURN_NOTOK;
}
OcGpio_write(chip_select, PIN_HIGH);
SPI_close(spiHandle);
return (status);
}
/*****************************************************************************
** FUNCTION NAME : spi_reg_write
**
** DESCRIPTION : Writing device register over SPI bus.
**
** ARGUMENTS : SPI handle, chip select, register address, data, data
**
** length, offset byte, numOfBytes for cmd write count
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
ReturnStatus spi_reg_write(SPI_Handle spiHandle,
OcGpio_Pin *chip_select,
void *regAddress,
uint8_t *data,
uint32_t data_size,
uint32_t byte,
uint8_t numofBytes)
{
ReturnStatus status = RETURN_OK;
SPI_Transaction spiTransaction;
spiTransaction.count = numofBytes; /* Initialize master SPI transaction structure */
spiTransaction.txBuf = regAddress;
spiTransaction.rxBuf = NULL;
OcGpio_write(chip_select, PIN_LOW); /* Initiate SPI transfer */
if (SPI_transfer(spiHandle, &spiTransaction)) {
status = RETURN_OK;
} else {
LOGGER_ERROR("SPIBUS:ERROR:: SPI write failed");
status = RETURN_NOTOK;
}
spiTransaction.count = data_size;
spiTransaction.txBuf = data;
spiTransaction.rxBuf = NULL;
if(data_size > 0) {
if (SPI_transfer(spiHandle, &spiTransaction)) {
status = RETURN_OK;
} else {
LOGGER_ERROR("SPIBUS:ERROR:: SPI write failed");
status = RETURN_NOTOK;
}
}
OcGpio_write(chip_select, PIN_HIGH);
SPI_close(spiHandle);
return (status);
}

View File

@@ -0,0 +1,271 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
* This file acts as wrapper for little filesystem, contains filesystem initialization,
* block read, block write, block erase as a main functions moreover provides API's
* like fileRead, fileWrite for external application to read and write data to
* at45db flash memory by using SPI interface.
*/
#include "Board.h"
#include "common/inc/global/Framework.h"
#include "common/inc/global/ocmp_frame.h"
#include "inc/common/bigbrother.h"
#include "inc/common/global_header.h"
#include "inc/devices/at45db.h"
#include "inc/global/OC_CONNECT1.h"
#include "inc/utils/util.h"
#include "src/filesystem/fs_wrapper.h"
#include "src/filesystem/lfs.h"
#include <string.h>
#include <stdlib.h>
#include <ti/drivers/GPIO.h>
#include <ti/drivers/SPI.h>
#include <ti/sysbios/BIOS.h>
#include <ti/sysbios/knl/Semaphore.h>
#include <ti/sysbios/knl/Queue.h>
#include <ti/sysbios/knl/Task.h>
#define BLOCK_SIZE 256
#define BLOCK_COUNT 32768
#define FRAME_SIZE 64
#define LOOK_AHEAD 256
#define PAGE_SIZE 256
#define READ_SIZE 256
#define WRITE_SIZE 256
static Queue_Struct fsRxMsg;
static Queue_Struct fsTxMsg;
lfs_t lfs;
lfs_file_t file;
/*****************************************************************************
** FUNCTION NAME : block_device_read
**
** DESCRIPTION : It is called by filesystem to read block device
**
** ARGUMENTS : context for device configuration, block or page number,
**
** block or page offset, data buffer, size of data to read
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
int block_device_read(const struct lfs_config *cfg, lfs_block_t block,
lfs_off_t off, void *buffer, lfs_size_t size)
{
if(at45db_data_read(cfg->context, buffer, size, off, block) != RETURN_OK) {
return LFS_ERR_IO;
}
return LFS_ERR_OK;
}
/*****************************************************************************
** FUNCTION NAME : block_device_write
**
** DESCRIPTION : it is called by filesystem to write block device
**
** ARGUMENTS : context for device configuration, block or page number,
**
** block or page offset, data buffer, size of data to write
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
int block_device_write(const struct lfs_config *cfg, lfs_block_t block,
lfs_off_t off, void *buffer, lfs_size_t size)
{
if(at45db_data_write(cfg->context, buffer, size, off, block) != RETURN_OK){
return LFS_ERR_IO;
}
return LFS_ERR_OK;
}
/*****************************************************************************
** FUNCTION NAME : block_device_erase
**
** DESCRIPTION : It is called by filesystem to erase block device
**
** ARGUMENTS : context for device configuration, block or page number,
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
int block_device_erase(const struct lfs_config *cfg, lfs_block_t block)
{
if(at45db_erasePage(cfg->context, block) != RETURN_OK) {
return LFS_ERR_IO;
}
return LFS_ERR_OK;
}
/*****************************************************************************
** FUNCTION NAME : block_device_sync
**
** DESCRIPTION : It is called by filesystem to sync with block device
**
** ARGUMENTS : context for device configuration
**
** RETURN TYPE : Success or failure
**
*****************************************************************************/
int block_device_sync(const struct lfs_config *cfg)
{
if(at45db_readStatusRegister(cfg->context) != RETURN_OK) {
return LFS_ERR_IO;
}
return LFS_ERR_OK;
}
/*****************************************************************************
** FUNCTION NAME : fileSize
**
** DESCRIPTION : Returns size of saved file
**
** ARGUMENTS : Path or file name
**
** RETURN TYPE : file size
**
*****************************************************************************/
int fileSize(const char *path)
{
uint32_t fileSize = 0;
if(lfs_file_open(&lfs, &file, path, LFS_O_RDONLY) == LFS_ERR_OK) {
LOGGER_DEBUG("FS:: File open successfully \n");
}
fileSize = lfs_file_size(&lfs, &file);
lfs_file_close(&lfs, &file);
return fileSize;
}
/*****************************************************************************
** FUNCTION NAME : fileWrite
**
** DESCRIPTION : It write data to specified file
**
** ARGUMENTS : Path or file name, pointer to data, data length or size
**
** RETURN TYPE : true or flase
**
*****************************************************************************/
bool fileWrite(const char *path, uint8_t *pMsg, uint32_t size )
{
if(lfs_file_open(&lfs, &file, path, LFS_O_RDWR | LFS_O_CREAT | LFS_O_APPEND) == LFS_ERR_OK) {
LOGGER_DEBUG("FS:: File open successfully \n");
}
if(lfs_file_write(&lfs, &file, pMsg, size) == size) {
LOGGER_DEBUG("FS:: File written successfully \n");
}
if(lfs_file_close(&lfs, &file) == LFS_ERR_OK) {
LOGGER_DEBUG("FS:: File closed successfully \n");
}
return true;
}
/*****************************************************************************
** FUNCTION NAME : fileRead
**
** DESCRIPTION : It reads data from specified file
**
** ARGUMENTS : Path or file name, pointer to data, data length or size
**
** RETURN TYPE : true or flase
**
*****************************************************************************/
bool fileRead(const char *path, UChar *buf, uint32_t size)
{
if(lfs_file_open(&lfs, &file, path, LFS_O_RDONLY) == LFS_ERR_OK) {
LOGGER_DEBUG("FS:: File open successfully \n");
}
if(lfs_file_read(&lfs, &file, buf, size) == size) {
LOGGER_DEBUG("FS:: File read successfully \n");
}
if(lfs_file_close(&lfs, &file) == LFS_ERR_OK) {
LOGGER_DEBUG("FS:: File closed successfully \n");
}
return true;
}
/*****************************************************************************
** FUNCTION NAME : fsMsgHandler
**
** DESCRIPTION : It is called when data to be written
**
** ARGUMENTS : data pointer
**
** RETURN TYPE : true or flase
**
*****************************************************************************/
static bool fsMsgHandler(OCMPMessageFrame *pMsg)
{
char fileName[] = "logs";
fileWrite(fileName, pMsg, FRAME_SIZE);
return true;
}
/*****************************************************************************
** FUNCTION NAME : fs_init
**
** DESCRIPTION : It initializes filesystem by mounting device
**
** ARGUMENTS : arg0 for SPI device configuration, arg1 for return
**
** RETURN TYPE : true or flase
**
*****************************************************************************/
void fs_init(UArg arg0, UArg arg1)
{
/*configuration of the filesystem is provided by this struct */
const struct lfs_config cfg = {
.context = (void*)arg0,
.read = block_device_read,
.prog = block_device_write,
.erase = block_device_erase,
.sync = block_device_sync,
.read_size = READ_SIZE,
.prog_size = WRITE_SIZE,
.block_size = BLOCK_SIZE,
.block_count = BLOCK_COUNT,
.lookahead = LOOK_AHEAD,
};
int err = lfs_mount(&lfs, &cfg);
if (err) {
lfs_format(&lfs, &cfg);
lfs_mount(&lfs, &cfg);
}
if(!err) {
LOGGER_DEBUG("FS:: Filesystem mounted successfully \n");
}
while (true) {
if (Semaphore_pend(semFilesysMsg, BIOS_WAIT_FOREVER)) {
while (!Queue_empty(fsTxMsgQueue)) {
OCMPMessageFrame *pMsg = (OCMPMessageFrame *)Util_dequeueMsg(fsTxMsgQueue);
if (pMsg != NULL) {
if (!fsMsgHandler(pMsg)) {
LOGGER_ERROR("ERROR:: Unable to route message \n");
free(pMsg);
}
}
}
}
}
}

View File

@@ -0,0 +1,25 @@
/**
* Copyright (c) 2017-present, Facebook, Inc.
* All rights reserved.
*
* This source code is licensed under the BSD-style license found in the
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*
*/
#ifndef SRC_FILESYSTEM_FS_H_
#define SRC_FILESYSTEM_FS_H_
#include "common/inc/global/post_frame.h"
extern Queue_Handle fsRxMsgQueue;
extern Queue_Handle fsTxMsgQueue;
extern Semaphore_Handle semFilesysMsg;
int fileSize(const char *path);
void fs_init(UArg arg0, UArg arg1);
bool fileRead(const char *path, UChar *buf, uint32_t size);
bool fileWrite(const char *path, uint8_t *pMsg, uint32_t size);
#endif /* SRC_FILESYSTEM_FS_H_ */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,330 @@
/*
* The little filesystem
*
* Copyright (c) 2017, Arm Limited. All rights reserved.
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef LFS_H
#define LFS_H
#include <stdbool.h>
#include <stdint.h>
/* Type definitions */
typedef uint32_t lfs_size_t;
typedef uint32_t lfs_off_t;
typedef int32_t lfs_ssize_t;
typedef int32_t lfs_soff_t;
typedef uint32_t lfs_block_t;
/* Max name size in bytes */
#ifndef LFS_NAME_MAX
#define LFS_NAME_MAX 255
#endif
/* Possible error codes, these are negative to allow
* valid positive return values
*/
enum lfs_error {
LFS_ERR_OK = 0, /* No error */
LFS_ERR_IO = -5, /* Error during device operation */
LFS_ERR_CORRUPT = -52, /* Corrupted */
LFS_ERR_NOENT = -2, /* No directory entry */
LFS_ERR_EXIST = -17, /* Entry already exists */
LFS_ERR_NOTDIR = -20, /* Entry is not a dir */
LFS_ERR_ISDIR = -21, /* Entry is a dir */
LFS_ERR_INVAL = -22, /* Invalid parameter */
LFS_ERR_NOSPC = -28, /* No space left on device */
LFS_ERR_NOMEM = -12, /* No more memory available */
};
/* File types */
enum lfs_type {
LFS_TYPE_REG = 0x11,
LFS_TYPE_DIR = 0x22,
LFS_TYPE_SUPERBLOCK = 0x2e,
};
/* File open flags */
enum lfs_open_flags {
/* open flags */
LFS_O_RDONLY = 1, /* Open a file as read only */
LFS_O_WRONLY = 2, /* Open a file as write only */
LFS_O_RDWR = 3, /* Open a file as read and write */
LFS_O_CREAT = 0x0100, /* Create a file if it does not exist */
LFS_O_EXCL = 0x0200, /* Fail if a file already exists */
LFS_O_TRUNC = 0x0400, /* Truncate the existing file to zero size */
LFS_O_APPEND = 0x0800, /* Move to end of file on every write */
/* internally used flags */
LFS_F_DIRTY = 0x10000, /* File does not match storage */
LFS_F_WRITING = 0x20000, /* File has been written since last flush */
LFS_F_READING = 0x40000, /* File has been read since last flush */
LFS_F_ERRED = 0x80000, /* An error occured during write */
};
/* File seek flags */
enum lfs_whence_flags {
LFS_SEEK_SET = 0, /* Seek relative to an absolute position */
LFS_SEEK_CUR = 1, /* Seek relative to the current file position */
LFS_SEEK_END = 2, /* Seek relative to the end of the file */
};
/* Configuration provided during initialization of the filesystem */
struct lfs_config {
void *context;
/* Read a region in a block */
int (*read)(const struct lfs_config *c, lfs_block_t block,
lfs_off_t off, void *buffer, lfs_size_t size);
/* Program a region in a block, function must return LFS_ERR_CORRUPT
* if the block should be considered bad
*/
int (*prog)(const struct lfs_config *c, lfs_block_t block,
lfs_off_t off, const void *buffer, lfs_size_t size);
/* Erase a block, A block must be erased before being programmed */
int (*erase)(const struct lfs_config *c, lfs_block_t block);
/* Sync the state of the underlying block device */
int (*sync)(const struct lfs_config *c);
/* Minimum size of a block read. This determines the size of read buffers.
* This may be larger than the physical read size to improve performance
* by caching more of the block device
*/
lfs_size_t read_size;
/* Minimum size of a block program. This determines the size of program
* buffers. This may be larger than the physical program size to improve
* performance by caching more of the block device.
*/
lfs_size_t prog_size;
/* Size of an erasable block. This does not impact ram consumption and
* may be larger than the physical erase size. However, this should be
* kept small as each file currently takes up an entire block .
*/
lfs_size_t block_size;
/* Number of erasable blocks on the device. */
lfs_size_t block_count;
/* Number of blocks to lookahead during block allocation. A larger
* lookahead reduces the number of passes required to allocate a block.
* The lookahead buffer requires only 1 bit per block so it can be quite
* large with little ram impact. Should be a multiple of 32.
*/
lfs_size_t lookahead;
/* Optional, statically allocated read buffer. Must be read sized. */
void *read_buffer;
/* Optional, statically allocated program buffer. Must be program sized. */
void *prog_buffer;
/* Optional, statically allocated lookahead buffer. Must be 1 bit per
* lookahead block
*/
void *lookahead_buffer;
/* Optional, statically allocated buffer for files. Must be program sized.
* If enabled, only one file may be opened at a time.
*/
void *file_buffer;
};
/* File info structure */
struct lfs_info {
/* Type of the file, either LFS_TYPE_REG or LFS_TYPE_DIR */
uint8_t type;
/* Size of the file, only valid for REG files */
lfs_size_t size;
/* Name of the file stored as a null-terminated string */
char name[LFS_NAME_MAX+1];
};
/* filesystem data structures */
typedef struct lfs_entry {
lfs_off_t off;
struct lfs_disk_entry {
uint8_t type;
uint8_t elen;
uint8_t alen;
uint8_t nlen;
union {
struct {
lfs_block_t head;
lfs_size_t size;
} file;
lfs_block_t dir[2];
} u;
} d;
} lfs_entry_t;
typedef struct lfs_cache {
lfs_block_t block;
lfs_off_t off;
uint8_t *buffer;
} lfs_cache_t;
typedef struct lfs_file {
struct lfs_file *next;
lfs_block_t pair[2];
lfs_off_t poff;
lfs_block_t head;
lfs_size_t size;
uint32_t flags;
lfs_off_t pos;
lfs_block_t block;
lfs_off_t off;
lfs_cache_t cache;
} lfs_file_t;
typedef struct lfs_dir {
struct lfs_dir *next;
lfs_block_t pair[2];
lfs_off_t off;
lfs_block_t head[2];
lfs_off_t pos;
struct lfs_disk_dir {
uint32_t rev;
lfs_size_t size;
lfs_block_t tail[2];
} d;
} lfs_dir_t;
typedef struct lfs_superblock {
lfs_off_t off;
struct lfs_disk_superblock {
uint8_t type;
uint8_t elen;
uint8_t alen;
uint8_t nlen;
lfs_block_t root[2];
uint32_t block_size;
uint32_t block_count;
uint32_t version;
char magic[8];
} d;
} lfs_superblock_t;
typedef struct lfs_free {
lfs_block_t begin;
lfs_block_t end;
lfs_block_t off;
uint32_t *buffer;
} lfs_free_t;
/* The filesystem type */
typedef struct lfs {
const struct lfs_config *cfg;
const struct lfs_config cfgs;
lfs_block_t root[2];
lfs_file_t *files;
lfs_dir_t *dirs;
lfs_cache_t rcache;
lfs_cache_t pcache;
lfs_free_t free;
bool deorphaned;
} lfs_t;
/* Format a block device with the filesystem */
int lfs_format(lfs_t *lfs, const struct lfs_config *config);
/* Mounts a filesystem */
int lfs_mount(lfs_t *lfs, const struct lfs_config *config);
/* Unmounts a filesystem */
int lfs_unmount(lfs_t *lfs);
/* Removes a file or directory */
int lfs_remove(lfs_t *lfs, const char *path);
/* Rename or move a file or directory */
int lfs_rename(lfs_t *lfs, const char *oldpath, const char *newpath);
/* Find info about a file or directory */
int lfs_stat(lfs_t *lfs, const char *path, struct lfs_info *info);
/* Open a file */
int lfs_file_open(lfs_t *lfs, lfs_file_t *file,
const char *path, int flags);
/* Close a file */
int lfs_file_close(lfs_t *lfs, lfs_file_t *file);
/* Synchronize a file on storage */
int lfs_file_sync(lfs_t *lfs, lfs_file_t *file);
/* Read data from file */
lfs_ssize_t lfs_file_read(lfs_t *lfs, lfs_file_t *file,
void *buffer, lfs_size_t size);
/* Write data to file */
lfs_ssize_t lfs_file_write(lfs_t *lfs, lfs_file_t *file,
const void *buffer, lfs_size_t size);
/* Change the position of the file */
lfs_soff_t lfs_file_seek(lfs_t *lfs, lfs_file_t *file,
lfs_soff_t off, int whence);
/* Return the position of the file */
lfs_soff_t lfs_file_tell(lfs_t *lfs, lfs_file_t *file);
/* Change the position of the file to the beginning of the file */
int lfs_file_rewind(lfs_t *lfs, lfs_file_t *file);
/* Return the size of the file */
lfs_soff_t lfs_file_size(lfs_t *lfs, lfs_file_t *file);
/* Create a directory */
int lfs_mkdir(lfs_t *lfs, const char *path);
/* Open a directory */
int lfs_dir_open(lfs_t *lfs, lfs_dir_t *dir, const char *path);
/* Close a directory */
int lfs_dir_close(lfs_t *lfs, lfs_dir_t *dir);
/* Read an entry in the directory */
int lfs_dir_read(lfs_t *lfs, lfs_dir_t *dir, struct lfs_info *info);
/* Change the position of the directory */
int lfs_dir_seek(lfs_t *lfs, lfs_dir_t *dir, lfs_off_t off);
/* Return the position of the directory */
lfs_soff_t lfs_dir_tell(lfs_t *lfs, lfs_dir_t *dir);
/* Change the position of the directory to the beginning of the directory */
int lfs_dir_rewind(lfs_t *lfs, lfs_dir_t *dir);
/* Traverse through all blocks in use by the filesystem */
int lfs_traverse(lfs_t *lfs, int (*cb)(void*, lfs_block_t), void *data);
/* Prunes any recoverable errors that may have occured in the filesystem
* Not needed to be called by user unless an operation is interrupted
* but the filesystem is still mounted. This is already called on first
* allocation.
* Returns a negative error code on failure.
*/
int lfs_deorphan(lfs_t *lfs);
#endif

View File

@@ -0,0 +1,24 @@
/*
* The little filesystem
*
* Copyright (c) 2017, Arm Limited. All rights reserved.
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "lfs_util.h"
void lfs_crc(uint32_t *restrict crc, const void *buffer, size_t size) {
static const uint32_t rtable[16] = {
0x00000000, 0x1db71064, 0x3b6e20c8, 0x26d930ac,
0x76dc4190, 0x6b6b51f4, 0x4db26158, 0x5005713c,
0xedb88320, 0xf00f9344, 0xd6d6a3e8, 0xcb61b38c,
0x9b64c2b0, 0x86d3d2d4, 0xa00ae278, 0xbdbdf21c,
};
const uint8_t *data = buffer;
for (size_t i = 0; i < size; i++) {
*crc = (*crc >> 4) ^ rtable[(*crc ^ (data[i] >> 0)) & 0xf];
*crc = (*crc >> 4) ^ rtable[(*crc ^ (data[i] >> 4)) & 0xf];
}
}

View File

@@ -0,0 +1,124 @@
/*
* The little filesystem
*
* Copyright (c) 2017, Arm Limited. All rights reserved.
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef LFS_UTIL_H
#define LFS_UTIL_H
#include <stdlib.h>
#include <stdint.h>
#include <stdio.h>
#ifdef __ICCARM__
#include <intrinsics.h>
#endif
/* Builtin functions, these may be replaced by more
* efficient implementations in the system
*/
static inline uint32_t lfs_max(uint32_t a, uint32_t b) {
return (a > b) ? a : b;
}
static inline uint32_t lfs_min(uint32_t a, uint32_t b) {
return (a < b) ? a : b;
}
static inline uint32_t lfs_ctz(uint32_t a) {
#if defined(__GNUC__) || defined(__CC_ARM)
return __builtin_ctz(a);
#elif defined(__ICCARM__)
return __CLZ(__RBIT(a));
#else
uint32_t r = 32;
a &= -a;
if (a) r -= 1;
if (a & 0x0000ffff) r -= 16;
if (a & 0x00ff00ff) r -= 8;
if (a & 0x0f0f0f0f) r -= 4;
if (a & 0x33333333) r -= 2;
if (a & 0x55555555) r -= 1;
return r;
#endif
}
static inline uint32_t lfs_npw2(uint32_t a) {
#if defined(__GNUC__) || defined(__CC_ARM)
return 32 - __builtin_clz(a-1);
#elif defined(__ICCARM__)
return 32 - __CLZ(a-1);
#else
uint32_t r = 0;
uint32_t s;
s = (a > 0xffff) << 4; a >>= s; r |= s;
s = (a > 0xff ) << 3; a >>= s; r |= s;
s = (a > 0xf ) << 2; a >>= s; r |= s;
s = (a > 0x3 ) << 1; a >>= s; r |= s;
return r | (a >> 1);
#endif
}
static inline uint32_t lfs_popc(uint32_t a) {
#if defined(__GNUC__) || defined(__CC_ARM)
return __builtin_popcount(a);
#else
a = a - ((a >> 1) & 0x55555555);
a = (a & 0x33333333) + ((a >> 2) & 0x33333333);
return (((a + (a >> 4)) & 0xf0f0f0f) * 0x1010101) >> 24;
#endif
}
static inline int lfs_scmp(uint32_t a, uint32_t b) {
return (int)(unsigned)(a - b);
}
/* CRC-32 with polynomial = 0x04c11db7 */
void lfs_crc(uint32_t *crc, const void *buffer, size_t size);
/* Logging functions */
#ifdef __MBED__
#include "mbed_debug.h"
#else
#define MBED_LFS_ENABLE_INFO false
#define MBED_LFS_ENABLE_DEBUG true
#define MBED_LFS_ENABLE_WARN true
#define MBED_LFS_ENABLE_ERROR true
#endif
#if MBED_LFS_ENABLE_INFO
#define LFS_INFO(fmt, ...) printf("lfs info: " fmt "\n", __VA_ARGS__)
#elif !defined(MBED_LFS_ENABLE_INFO)
#define LFS_INFO(fmt, ...) debug("lfs info: " fmt "\n", __VA_ARGS__)
#else
#define LFS_INFO(fmt, ...)
#endif
#if MBED_LFS_ENABLE_DEBUG
#define LFS_DEBUG(fmt, ...) printf("lfs debug: " fmt "\n", __VA_ARGS__)
#elif !defined(MBED_LFS_ENABLE_DEBUG)
#define LFS_DEBUG(fmt, ...) debug("lfs debug: " fmt "\n", __VA_ARGS__)
#else
#define LFS_DEBUG(fmt, ...)
#endif
#if MBED_LFS_ENABLE_WARN
#define LFS_WARN(fmt, ...) printf("lfs warn: " fmt "\n", __VA_ARGS__)
#elif !defined(MBED_LFS_ENABLE_WARN)
#define LFS_WARN(fmt, ...) debug("lfs warn: " fmt "\n", __VA_ARGS__)
#else
#define LFS_WARN(fmt, ...)
#endif
#if MBED_LFS_ENABLE_ERROR
#define LFS_ERROR(fmt, ...) printf("lfs error: " fmt "\n", __VA_ARGS__)
#elif !defined(MBED_LFS_ENABLE_ERROR)
#define LFS_ERROR(fmt, ...) debug("lfs error: " fmt "\n", __VA_ARGS__)
#else
#define LFS_ERROR(fmt, ...)
#endif
#endif

View File

@@ -62,6 +62,7 @@ int main(void)
Board_initGeneral();
Board_initGPIO();
Board_initI2C();
Board_initSPI();
Board_initUSB(Board_USBDEVICE);
Board_initUART();
ethernet_start();

View File

@@ -6,20 +6,43 @@
* LICENSE file in the root directory of this source tree. An additional grant
* of patent rights can be found in the PATENTS file in the same directory.
*/
#include "inc/subsystem/sys/sys.h"
#include "common/inc/global/Framework.h"
#include "helpers/memory.h"
#include "inc/common/bigbrother.h"
#include "inc/common/global_header.h"
#include "inc/common/post.h"
#include "inc/devices/eeprom.h"
#include "inc/subsystem/gpp/gpp.h" /* For resetting AP */
#include "inc/subsystem/sys/sys.h"
#include "inc/utils/ocmp_util.h"
#include "src/filesystem/fs_wrapper.h"
#include <driverlib/flash.h>
#include <driverlib/sysctl.h>
#include <ti/sysbios/BIOS.h>
#include <ti/sysbios/knl/Semaphore.h>
#include <ti/sysbios/knl/Queue.h>
#include <ti/sysbios/knl/Task.h>
#include <xdc/std.h>
#include <xdc/cfg/global.h>
#include <xdc/runtime/System.h>
#include <stdio.h>
#include <string.h>
#define FRAME_SIZE 64
#define OCFS_TASK_PRIORITY 5
#define OCFS_TASK_STACK_SIZE 4096
#define OC_MAC_ADDRESS_SIZE 13
Task_Struct ocFSTask;
Char ocFSTaskStack[OCFS_TASK_STACK_SIZE];
Semaphore_Handle semFilesysMsg;
Semaphore_Struct semFSstruct;
static Queue_Struct fsRxMsg;
static Queue_Struct fsTxMsg;
Queue_Handle fsRxMsgQueue;
Queue_Handle fsTxMsgQueue;
extern POSTData PostResult[POST_RECORDS];
@@ -54,7 +77,6 @@ bool SYS_cmdEcho(void *driver, void *params)
return true;
}
/*
/*****************************************************************************
** FUNCTION NAME : SYS_post_enable
**
@@ -137,3 +159,30 @@ bool SYS_post_get_results(void **getpostResult)
memcpy(((OCMPMessageFrame*)getpostResult), postResultMsg, 64);
return status;
}
bool sys_post_init(void* driver, void *returnValue)
{
Semaphore_construct(&semFSstruct, 0, NULL);
semFilesysMsg = Semaphore_handle(&semFSstruct);
if (!semFilesysMsg) {
LOGGER_DEBUG("FS:ERROR:: Failed in Creating Semaphore");
return false;
}
/* Create Message Queue for RX Messages */
fsTxMsgQueue = Util_constructQueue(&fsTxMsg);
if (!fsTxMsgQueue) {
LOGGER_ERROR("FS:ERROR:: Failed in Constructing Message Queue for");
return false;
}
Task_Params taskParams;
Task_Params_init(&taskParams);
taskParams.stackSize = OCFS_TASK_STACK_SIZE;
taskParams.stack = &ocFSTaskStack;
taskParams.instance->name = "FS_TASK";
taskParams.priority = OCFS_TASK_PRIORITY;
taskParams.arg0 = (UArg)driver;
taskParams.arg1 = (UArg)returnValue;
Task_construct(&ocFSTask,fs_init, &taskParams,NULL);
LOGGER_DEBUG("FS:INFO:: Creating filesystem task function.\n");
return true;
}