add rt-kernel xmc4 hal, support SM/DC sync

pull/32/head
rtlaka 2017-10-25 19:13:54 +02:00
parent 06c2c30890
commit 59d38dca2c
4 changed files with 845 additions and 0 deletions

View File

@ -0,0 +1,305 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* ESC hardware layer functions.
*
* Function to read and write commands to the ESC. Used to read/write ESC
* registers and memory.
*/
#include <kern.h>
#include <bsp.h>
#include <xmc4.h>
#include <eru.h>
#include <string.h>
#include "esc_hw.h"
#include "slave.h"
#include "esc_eep.h"
#define ESCADDR(x) (((uint8_t *) ECAT0_BASE) + x)
static volatile esc_registers_t * ecat0 = (esc_registers_t *)ECAT0_BASE;
static int use_all_interrupts = 0;
static sem_t * ecat_isr_sem;
static void sync0_isr (void * arg);
static volatile uint8_t read_ack;
static const eru_cfg_t cfg = {
.base = ERU1_BASE,
.channel = 2,
.in_a = 0,
.in_b = 3,
.exicon = ERU_EXICON_PE_ENABLED |
ERU_EXICON_LD_ENABLED |
ERU_EXICON_RE_ENABLED |
ERU_EXICON_OCS(2) |
ERU_EXICON_SS(1),
.exocon = ERU_EXOCON_ISS(0) |
ERU_EXOCON_GP(1) |
ERU_EXOCON_IPEEN(0),
.irq = IRQ_ERU1_SR7,
.isr = sync0_isr,
.arg = NULL,
};
static const scu_ecat_cfg_t port_control =
{
.con = {0},
.conp0 = {
.rxd[0] = ECAT_PORT0_CTRL_RXDO0,
.rxd[1] = ECAT_PORT0_CTRL_RXDO1,
.rxd[2] = ECAT_PORT0_CTRL_RXDO2,
.rxd[3] = ECAT_PORT0_CTRL_RXDO3,
.rx_clk = ECAT_PORT0_CTRL_RX_CLK,
.rx_dv = ECAT_PORT0_CTRL_RX_DV,
.rx_err = ECAT_PORT0_CTRL_RX_ERR,
.link = ECAT_PORT0_CTRL_LINK,
.tx_clk = ECAT_PORT0_CTRL_TX_CLK,
.tx_shift = ECAT_PORT0_CTRL_TX_SHIFT
},
.conp1 = {
.rxd[0] = ECAT_PORT1_CTRL_RXDO0,
.rxd[1] = ECAT_PORT1_CTRL_RXDO1,
.rxd[2] = ECAT_PORT1_CTRL_RXDO2,
.rxd[3] = ECAT_PORT1_CTRL_RXDO3,
.rx_clk = ECAT_PORT1_CTRL_RX_CLK,
.rx_dv = ECAT_PORT1_CTRL_RX_DV,
.rx_err = ECAT_PORT1_CTRL_RX_ERR,
.link = ECAT_PORT1_CTRL_LINK,
.tx_clk = ECAT_PORT1_CTRL_TX_CLK,
.tx_shift = ECAT_PORT1_CTRL_TX_SHIFT
}
};
/* EtherCAT module clock ungating and deassert reset API (Enables ECAT) */
void ESC_enable(void)
{
scu_put_peripheral_in_reset (SCU_PERIPHERAL_ECAT0);
scu_ungate_clock_to_peripheral (SCU_PERIPHERAL_ECAT0);
scu_release_peripheral_from_reset (SCU_PERIPHERAL_ECAT0);
}
/* EtherCAT module clock gating and assert reset API (Disables ECAT)*/
void ESC_disable(void)
{
scu_put_peripheral_in_reset (SCU_PERIPHERAL_ECAT0);
scu_gate_clock_to_peripheral (SCU_PERIPHERAL_ECAT0);
}
/** ESC read function used by the Slave stack.
*
* @param[in] address = address of ESC register to read
* @param[out] buf = pointer to buffer to read in
* @param[in] len = number of bytes to read
*/
void ESC_read (uint16_t address, void *buf, uint16_t len)
{
if(use_all_interrupts == 0)
{
ESCvar.ALevent = etohs ((uint16_t)ecat0->AL_EVENT_REQ);
}
memcpy (buf, ESCADDR(address), len);
}
/** ESC write function used by the Slave stack.
*
* @param[in] address = address of ESC register to write
* @param[out] buf = pointer to buffer to write from
* @param[in] len = number of bytes to write
*/
void ESC_write (uint16_t address, void *buf, uint16_t len)
{
if(use_all_interrupts == 0)
{
ESCvar.ALevent = etohs ((uint16_t)ecat0->AL_EVENT_REQ);
}
memcpy (ESCADDR(address), buf, len);
}
/** ESC reset hardware.
*/
void ESC_reset (void)
{
/* disable ESC to force reset */
ESC_disable ();
/* initialize EEPROM emulation */
EEP_init ();
}
/** ESC interrupt enable function by the Slave stack in IRQ mode.
*
* @param[in] mask = of interrupts to enable
*/
void ESC_interrupt_enable (uint32_t mask)
{
if(ESCREG_ALEVENT_DC_SYNC0 & mask)
{
mask &= ~ESCREG_ALEVENT_DC_SYNC0;
int_enable(cfg.irq);
}
if(ESCREG_ALEVENT_DC_SYNC1 & mask)
{
mask &= ~ESCREG_ALEVENT_DC_SYNC1;
UASSERT(0,EARG);
}
if(ESCREG_ALEVENT_DC_LATCH & mask)
{
mask &= ~ESCREG_ALEVENT_DC_LATCH;
UASSERT(0,EARG);
}
ecat0->AL_EVENT_MASK |= mask;
}
/** ESC interrupt disable function by the Slave stack in IRQ mode.
*
* @param[in] mask = interrupts to disable
*/
void ESC_interrupt_disable (uint32_t mask)
{
if(ESCREG_ALEVENT_DC_SYNC0 & mask)
{
mask &= ~ESCREG_ALEVENT_DC_SYNC0;
int_disable(cfg.irq);
}
if(ESCREG_ALEVENT_DC_SYNC1 & mask)
{
mask &= ~ESCREG_ALEVENT_DC_SYNC1;
UASSERT(0,EARG);
}
if(ESCREG_ALEVENT_DC_LATCH & mask)
{
mask &= ~ESCREG_ALEVENT_DC_LATCH;
UASSERT(0,EARG);
}
ecat0->AL_EVENT_MASK &= ~mask;
}
/** ESC emulated EEPROM handler
*/
void ESC_eep_handler(void)
{
EEP_process ();
EEP_hw_process();
}
/** SYNC0 ISR handler
*
* @param[in] arg = NOT USED
*/
static void sync0_isr (void * arg)
{
DIG_process(DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
read_ack = ecat0->DC_SYNC0_STAT;
}
/** PDI ISR handler
*
* @param[in] arg = NOT USED
*/
static void ecat_isr (void * arg)
{
ESC_read (ESCREG_LOCALTIME, (void *) &ESCvar.Time, sizeof (ESCvar.Time));
ESCvar.Time = etohl (ESCvar.Time);
CC_ATOMIC_SET(ESCvar.ALevent, etohl(ecat0->AL_EVENT_REQ));
if(ESCvar.ALevent & ESCREG_ALEVENT_SM2)
{
if(dc_sync == 0)
{
DIG_process(DIG_PROCESS_OUTPUTS_FLAG | DIG_PROCESS_APP_HOOK_FLAG |
DIG_PROCESS_INPUTS_FLAG);
}
else
{
DIG_process(DIG_PROCESS_OUTPUTS_FLAG);
}
}
if(ESCvar.ALevent & (ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP))
{
/* Mask interrupts while servicing them */
ecat0->AL_EVENT_MASK &= ~(ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP);
sem_signal(ecat_isr_sem);
}
}
/* Function for PDI ISR serving task */
static void isr_run(void * arg)
{
while(1)
{
sem_wait(ecat_isr_sem);
ecat_slv_isr();
}
}
/** ESC and CPU related HW init
*
* @param[in] arg = esc_cfg provided by the application
*/
void ESC_init (const esc_cfg_t * config)
{
eep_config_t ecat_config;
ESC_reset();
scu_configure_ethercat_signals(&port_control);
/* read config from emulated EEPROM */
memset(&ecat_config, 0, sizeof(eep_config_t));
EEP_read (0, (uint8_t *) &ecat_config, sizeof(eep_config_t));
ESC_enable();
/* words 0x0-0x3 */
ecat0->EEP_DATA[0U] = ecat_config.dword[0U];
ecat0->EEP_DATA[1U] = ecat_config.dword[1U];
ecat0->EEP_CONT_STAT |= (uint16_t)(BIT(10)); /* ESI EEPROM Reload */
/* words 0x4-0x7 */
ecat0->EEP_DATA[0U] = ecat_config.dword[2U];
ecat0->EEP_DATA[1U] = ecat_config.dword[3U];
ecat0->EEP_CONT_STAT |= (uint16_t)(BIT(10)); /* ESI EEPROM Reload */
while (ecat0->EEP_CONT_STAT & BIT(12)) /* ESI EEPROM loading status */
{
/* Wait until the EEPROM_Loaded signal is active */
}
/* Configure CPU interrupts */
if(config->use_interrupt != 0)
{
ecat_isr_sem = sem_create(0);
task_spawn ("soes_isr", isr_run, 9, 2048, NULL);
use_all_interrupts = 1;
ecat0->AL_EVENT_MASK = 0;
ecat0->AL_EVENT_MASK = (ESCREG_ALEVENT_SMCHANGE |
ESCREG_ALEVENT_EEP |
ESCREG_ALEVENT_CONTROL |
ESCREG_ALEVENT_SM0 |
ESCREG_ALEVENT_SM1);
int_connect (IRQ_ECAT0_SR0, ecat_isr, NULL);
int_enable (IRQ_ECAT0_SR0);
/* Activate for running external sync IRQ */
scu_put_peripheral_in_reset (SCU_PERIPHERAL_ERU1);
scu_ungate_clock_to_peripheral (SCU_PERIPHERAL_ERU1);
scu_release_peripheral_from_reset (SCU_PERIPHERAL_ERU1);
eru_configure(&cfg);
/* Let the stack decide when to enable */
int_disable(cfg.irq);
}
}

View File

@ -0,0 +1,175 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* ESC hardware specifoc EEPROM emulation functions.
*/
#ifndef __esc_hw__
#define __esc_hw__
#include <kern.h>
/* ================================================================================ */
/* ================ ECAT [ECAT0] ================ */
/* ================================================================================ */
/**
* @brief EtherCAT 0 (ECAT)
*/
typedef struct esc_registers
{ /*!< (@ 0x54010000) ECAT Structure */
uint8_t TYPE; /*!< (@ 0x54010000) Type of EtherCAT Controller */
uint8_t REVISION; /*!< (@ 0x54010001) Revision of EtherCAT Controller */
uint16_t BUILD; /*!< (@ 0x54010002) Build Version */
uint8_t FMMU_NUM; /*!< (@ 0x54010004) FMMUs Supported */
uint8_t SYNC_MANAGER; /*!< (@ 0x54010005) SyncManagers Supported */
uint8_t RAM_SIZE; /*!< (@ 0x54010006) RAM Size */
uint8_t PORT_DESC; /*!< (@ 0x54010007) Port Descriptor */
uint16_t FEATURE; /*!< (@ 0x54010008) ESC Features Supported */
uint16_t RESERVED[3];
uint16_t STATION_ADR; /*!< (@ 0x54010010) Configured Station Address */
uint16_t STATION_ALIAS; /*!< (@ 0x54010012) Configured Station Alias */
uint32_t RESERVED1[3];
uint8_t WR_REG_ENABLE; /*!< (@ 0x54010020) Write Register Enable */
uint8_t WR_REG_PROTECT; /*!< (@ 0x54010021) Write Register Protection */
uint16_t RESERVED2[7];
uint8_t ESC_WR_ENABLE; /*!< (@ 0x54010030) ESC Write Enable */
uint8_t ESC_WR_PROTECT; /*!< (@ 0x54010031) ESC Write Protection */
uint16_t RESERVED3[7];
union
{
uint8_t ESC_RESET_ECAT_READMode; /*!< (@ 0x54010040) ESC Reset ECAT [READ Mode] */
uint8_t ESC_RESET_ECAT_WRITEMode; /*!< (@ 0x54010040) ESC Reset ECAT [WRITE Mode] */
};
union {
uint8_t ESC_RESET_PDI_READMode; /*!< (@ 0x54010041) ESC Reset PDI [READ Mode] */
uint8_t ESC_RESET_PDI_WRITEMode; /*!< (@ 0x54010041) ESC Reset PDI [WRITE Mode] */
};
uint16_t RESERVED4[95];
uint32_t ESC_DL_CONTROL; /*!< (@ 0x54010100) ESC DL Control */
uint32_t RESERVED5;
uint16_t PHYSICAL_RW_OFFSET; /*!< (@ 0x54010108) Physical Read/Write Offset */
uint16_t RESERVED6[3];
uint16_t ESC_DL_STATUS; /*!< (@ 0x54010110) ESC DL Status */
uint16_t RESERVED7[7];
uint16_t AL_CONTROL; /*!< (@ 0x54010120) AL Control */
uint16_t RESERVED8[7];
uint16_t AL_STATUS; /*!< (@ 0x54010130) AL Status */
uint16_t RESERVED9;
uint16_t AL_STATUS_CODE; /*!< (@ 0x54010134) AL Status Code */
uint16_t RESERVED10;
uint8_t RUN_LED; /*!< (@ 0x54010138) RUN LED Override */
uint8_t ERR_LED; /*!< (@ 0x54010139) RUN ERR Override */
uint16_t RESERVED11[3];
uint8_t PDI_CONTROL; /*!< (@ 0x54010140) PDI Control */
uint8_t ESC_CONFIG; /*!< (@ 0x54010141) ESC Configuration */
uint16_t RESERVED12[7];
uint8_t PDI_CONFIG; /*!< (@ 0x54010150) PDI Control */
uint8_t SYNC_LATCH_CONFIG; /*!< (@ 0x54010151) Sync/Latch[1:0] PDI Configuration */
uint16_t PDI_EXT_CONFIG; /*!< (@ 0x54010152) PDI Synchronous Microcontroller extended Configuration */
uint32_t RESERVED13[43];
uint16_t EVENT_MASK; /*!< (@ 0x54010200) ECAT Event Mask */
uint16_t RESERVED14;
uint32_t AL_EVENT_MASK; /*!< (@ 0x54010204) PDI AL Event Mask */
uint32_t RESERVED15[2];
uint16_t EVENT_REQ; /*!< (@ 0x54010210) ECAT Event Request */
uint16_t RESERVED16[7];
uint32_t AL_EVENT_REQ; /*!< (@ 0x54010220) AL Event Request */
uint32_t RESERVED17[55];
uint16_t RX_ERR_COUNT0; /*!< (@ 0x54010300) RX Error Counter Port 0 */
uint16_t RX_ERR_COUNT1; /*!< (@ 0x54010302) RX Error Counter Port 1 */
uint32_t RESERVED18;
uint8_t FWD_RX_ERR_COUNT0; /*!< (@ 0x54010308) Forwarded RX Error Counter Port 0 */
uint8_t FWD_RX_ERR_COUNT1; /*!< (@ 0x54010309) Forwarded RX Error Counter Port 1 */
uint16_t RESERVED19;
uint8_t PROC_ERR_COUNT; /*!< (@ 0x5401030C) ECAT Processing Unit Error Counter */
uint8_t PDI_ERR_COUNT; /*!< (@ 0x5401030D) PDI Error Counter */
uint16_t RESERVED20;
uint8_t LOST_LINK_COUNT0; /*!< (@ 0x54010310) Lost Link Counter Port 0 */
uint8_t LOST_LINK_COUNT1; /*!< (@ 0x54010311) Lost Link Counter Port 1 */
uint16_t RESERVED21[119];
uint16_t WD_DIVIDE; /*!< (@ 0x54010400) Watchdog Divider */
uint16_t RESERVED22[7];
uint16_t WD_TIME_PDI; /*!< (@ 0x54010410) Watchdog Time PDI */
uint16_t RESERVED23[7];
uint16_t WD_TIME_PDATA; /*!< (@ 0x54010420) Watchdog Time Process Data */
uint16_t RESERVED24[15];
uint16_t WD_STAT_PDATA; /*!< (@ 0x54010440) Watchdog Status Process Data */
uint8_t WD_COUNT_PDATA; /*!< (@ 0x54010442) Watchdog Counter Process Data */
uint8_t WD_COUNT_PDI; /*!< (@ 0x54010443) Watchdog Counter PDI */
uint32_t RESERVED25[47];
uint8_t EEP_CONF; /*!< (@ 0x54010500) EEPROM Configuration */
uint8_t EEP_STATE; /*!< (@ 0x54010501) EEPROM PDI Access State */
uint16_t EEP_CONT_STAT; /*!< (@ 0x54010502) EEPROM Control/Status */
uint32_t EEP_ADR; /*!< (@ 0x54010504) EEPROM Address */
uint32_t EEP_DATA[2]; /*!< (@ 0x54010508) EEPROM Read/Write data */
uint16_t MII_CONT_STAT; /*!< (@ 0x54010510) MII Management Control/Status */
uint8_t MII_PHY_ADR; /*!< (@ 0x54010512) PHY Address */
uint8_t MII_PHY_REG_ADR; /*!< (@ 0x54010513) PHY Register Address */
uint16_t MII_PHY_DATA; /*!< (@ 0x54010514) PHY Data */
uint8_t MII_ECAT_ACS_STATE; /*!< (@ 0x54010516) MII ECAT ACS STATE */
uint8_t MII_PDI_ACS_STATE; /*!< (@ 0x54010517) MII PDI ACS STATE */
uint32_t RESERVED26[250];
uint32_t DC_RCV_TIME_PORT0; /*!< (@ 0x54010900) Receive Time Port 0 */
uint32_t DC_RCV_TIME_PORT1; /*!< (@ 0x54010904) Receive Time Port 1 */
uint32_t RESERVED27[2];
union
{
uint32_t READMode_DC_SYS_TIME[2]; /*!< (@ 0x54010910) System Time read access */
uint32_t DC_SYS_TIME_WRITEMode; /*!< (@ 0x54010910) System Time [WRITE Mode] */
};
uint32_t RECEIVE_TIME_PU[2]; /*!< (@ 0x54010918) Local time of the beginning of a frame */
uint32_t DC_SYS_TIME_OFFSET[2]; /*!< (@ 0x54010920) Difference between local time and System Time */
uint32_t DC_SYS_TIME_DELAY; /*!< (@ 0x54010928) System Time Delay */
uint32_t DC_SYS_TIME_DIFF; /*!< (@ 0x5401092C) System Time Difference */
uint16_t DC_SPEED_COUNT_START; /*!< (@ 0x54010930) Speed Counter Start */
uint16_t DC_SPEED_COUNT_DIFF; /*!< (@ 0x54010932) Speed Counter Diff */
uint8_t DC_SYS_TIME_FIL_DEPTH; /*!< (@ 0x54010934) System Time Difference Filter Depth */
uint8_t DC_SPEED_COUNT_FIL_DEPTH; /*!< (@ 0x54010935) Speed Counter Filter Depth */
uint16_t RESERVED28[37];
uint8_t DC_CYC_CONT; /*!< (@ 0x54010980) Cyclic Unit Control */
uint8_t DC_ACT; /*!< (@ 0x54010981) Activation register */
uint16_t DC_PULSE_LEN; /*!< (@ 0x54010982) Pulse Length of SyncSignals */
uint8_t DC_ACT_STAT; /*!< (@ 0x54010984) Activation Status */
uint8_t RESERVED29[9];
uint8_t DC_SYNC0_STAT; /*!< (@ 0x5401098E) SYNC0 Status */
uint8_t DC_SYNC1_STAT; /*!< (@ 0x5401098F) SYNC1 Status */
uint32_t DC_CYC_START_TIME[2]; /*!< (@ 0x54010990) Start Time Cyclic Operation */
uint32_t DC_NEXT_SYNC1_PULSE[2]; /*!< (@ 0x54010998) System time of next SYNC1 pulse in ns */
uint32_t DC_SYNC0_CYC_TIME; /*!< (@ 0x540109A0) SYNC0 Cycle Time */
uint32_t DC_SYNC1_CYC_TIME; /*!< (@ 0x540109A4) SYNC1 Cycle Time */
uint8_t DC_LATCH0_CONT; /*!< (@ 0x540109A8) Latch0 Control */
uint8_t DC_LATCH1_CONT; /*!< (@ 0x540109A9) Latch1 Control */
uint32_t RESERVED30;
uint8_t DC_LATCH0_STAT; /*!< (@ 0x540109AE) Latch0 Status */
uint8_t DC_LATCH1_STAT; /*!< (@ 0x540109AF) Latch1 Status */
uint32_t DC_LATCH0_TIME_POS[2]; /*!< (@ 0x540109B0) Register captures System time at the positive
edge of the Latch0 signal */
uint32_t DC_LATCH0_TIME_NEG[2]; /*!< (@ 0x540109B8) Register captures System time at the negative
edge of the Latch0 signal */
uint32_t DC_LATCH1_TIME_POS[2]; /*!< (@ 0x540109C0) Register captures System time at the positive
edge of the Latch1 signal */
uint32_t DC_LATCH1_TIME_NEG[2]; /*!< (@ 0x540109C8) Register captures System time at the negative
edge of the Latch1 signal */
uint32_t RESERVED31[8];
uint32_t DC_ECAT_CNG_EV_TIME; /*!< (@ 0x540109F0) EtherCAT Buffer Change Event Time */
uint32_t RESERVED32;
uint32_t DC_PDI_START_EV_TIME; /*!< (@ 0x540109F8) PDI Buffer Start Event Time */
uint32_t DC_PDI_CNG_EV_TIME; /*!< (@ 0x540109FC) PDI Buffer Change Event Time */
uint32_t RESERVED33[256];
uint32_t ID; /*!< (@ 0x54010E00) ECAT0 Module ID */
uint32_t RESERVED34;
uint32_t STATUS; /*!< (@ 0x54010E08) ECAT0 Status */
} esc_registers_t;
void EEP_hw_process (void);
void ESC_eep_handler(void);
void ESC_interrupt_enable (uint32_t mask);
void ESC_interrupt_disable (uint32_t mask);
#endif

View File

@ -0,0 +1,311 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* ESC hardware specific EEPROM emulation functions.
*/
#include <cc.h>
#include <fce.h>
#include <string.h>
#include <drivers/nor/nor.h>
#include "esc.h"
#include "esc_hw_eep.h"
extern const uint8_t _binary_sii_eeprom_bin_start;
extern const uint8_t _binary_sii_eeprom_bin_end;
#define SII_EE_DEFLT (&_binary_sii_eeprom_bin_start)
#define SII_EE_DEFLT_SIZE (uint32_t)(&_binary_sii_eeprom_bin_end - &_binary_sii_eeprom_bin_start)
#define EEP_DEFAULT_BTN_INIT() { }
#define EEP_DEFAULT_BTN_STATE() 0
#define EEP_BUSY_LED_INIT() { }
#define EEP_BUSY_LED_ON() { }
#define EEP_BUSY_LED_OFF() { }
#if EEP_BYTES_PER_BLOCK > EEP_BYTES_PER_SECTOR
#error EEP_BYTES_PER_BLOCK needs to fit into EEP_BYTES_PER_SECTOR
#endif
/** CRC engine configuration */
static const fce_kernel_cfg_t fce_config =
{
.crc_kernel_addr = FCE_KE0_BASE,
.kernel_cfg = 0,
.seed = 0xffffffff
};
static uint8_t eep_buf[EEP_EMU_BYTES];
static uint8_t eep_buf_dirty;
static uint32_t eep_last_write;
static uint8_t eep_write_req;
static eep_block_t *eep_curr_block;
static eep_block_t *eep_next_block;
static uint32_t *eep_write_src;
static uint32_t *eep_write_dst;
static uint32_t eep_write_page;
static eep_block_t eep_write_buf;
static drv_t * drv;
static void init_flash_data(void);
static void find_latest_block(eep_block_t *addr);
static eep_block_t *get_next_block(eep_block_t *block);
static eep_block_t *cleanup_unused_sect(eep_block_t *block);
static int32_t is_sector_empty(uint32_t *addr);
/** Initialize EEPROM emulation (load default data, validate checksums, ...).
*
*/
void EEP_init (void)
{
/* initialize write buffer */
memset(&eep_write_buf, 0, EEP_BYTES_PER_BLOCK);
/* Initialize the FCE Configuration */
fce_init(&fce_config);
drv = dev_find_driver ("/pflash");
ASSERT (drv != NULL);
/* try to find latest block in both sectors */
eep_curr_block = NULL;
if (!EEP_DEFAULT_BTN_STATE()) {
find_latest_block((eep_block_t *) EEP_SECTOR_A);
find_latest_block((eep_block_t *) EEP_SECTOR_B);
}
EEP_BUSY_LED_ON();
/* no valid block found -> initialize flash with default data */
if (eep_curr_block == NULL) {
init_flash_data();
}
/* cleanup unused block */
cleanup_unused_sect(eep_curr_block);
/* copy data from block to emu buffer */
memcpy(eep_buf, eep_curr_block->data, EEP_EMU_BYTES);
/* initialize state variables */
eep_buf_dirty = 0;
eep_last_write = 0;
eep_write_req = 0;
eep_next_block = NULL;
}
/** EEPROM emulation controller side periodic task.
*
*/
void EEP_hw_process (void)
{
/* check for dirty buffer and set write */
if (eep_buf_dirty) {
int32_t idle_time = ((int32_t) ESCvar.Time) - ((int32_t) eep_last_write);
if (idle_time > EEP_IDLE_TIMEOUT) {
eep_buf_dirty = 0;
eep_write_req = 1;
}
}
/* check for write process */
if (eep_next_block != NULL) {
/* write flash page */
nor_write(drv, EEP_FLASH_SECTOR_OFFSET((uint32_t)eep_write_dst),
EEP_BYTES_PER_PAGE, (const uint8_t *)eep_write_src);
eep_write_src += (EEP_BYTES_PER_PAGE / sizeof(*eep_write_src));
eep_write_dst += (EEP_BYTES_PER_PAGE / sizeof(*eep_write_dst));
/* update counter */
eep_write_page++;
/* check for finished job */
if (eep_write_page >= EEP_PAGES_PER_BLOCK) {
/* update block pointer and reset write state */
eep_curr_block = eep_next_block;
eep_next_block = NULL;
}
return;
}
/* start write of new block */
if (eep_write_req) {
EEP_BUSY_LED_ON();
/* get next block */
eep_next_block = get_next_block(eep_curr_block);
/* copy data */
memcpy(eep_write_buf.data, eep_buf, EEP_EMU_BYTES);
/* setup header */
eep_write_buf.header.seq = eep_curr_block->header.seq + 1;
eep_write_buf.header.crc = fce_crc32 (&fce_config,
(const uint32_t *)eep_write_buf.data, EEP_DATA_BYTES);
/* initialize write position */
eep_write_src = (uint32_t *) &eep_write_buf;
eep_write_dst = (uint32_t *) eep_next_block;
eep_write_page = 0;
/* reset write request */
eep_write_req = 0;
}
}
/** EEPROM read function
*
* @param[in] addr = EEPROM byte address
* @param[out] data = pointer to buffer of output data
* @param[in] count = number of bytes to read
* @return 0 on OK, 1 on error
*/
int8_t EEP_read (uint32_t addr, uint8_t *data, uint16_t count)
{
if (addr >= EEP_EMU_BYTES) {
return 1;
}
/* read data from ram buffer */
memcpy(data, eep_buf + addr, count);
return 0;
}
/** EEPROM write function
*
* @param[in] addr = EEPROM byte address
* @param[out] data = pointer to buffer of input data
* @param[in] count = number of bytes to write
* @return 0 on OK, 1 on error
*/
int8_t EEP_write (uint32_t addr, uint8_t *data, uint16_t count)
{
if (addr >= EEP_EMU_BYTES) {
return 1;
}
/* write data to ram buffer */
memcpy(eep_buf + addr, data, count);
/* mark buffer as dirty */
eep_buf_dirty = 1;
eep_write_req = 0;
eep_last_write = ESCvar.Time;
return 0;
}
static void init_flash_data(void)
{
uint32_t i;
const uint32_t *src;
uint32_t dst;
/* erase both sectors */
nor_erase(drv, EEP_FLASH_SECTOR_OFFSET(EEP_SECTOR_A), EEP_BYTES_PER_SECTOR);
nor_erase(drv, EEP_FLASH_SECTOR_OFFSET(EEP_SECTOR_B), EEP_BYTES_PER_SECTOR);
/* copy default data to write buffer */
memcpy(eep_write_buf.data, SII_EE_DEFLT, (SII_EE_DEFLT_SIZE < EEP_EMU_BYTES) ? SII_EE_DEFLT_SIZE : EEP_EMU_BYTES);
/*
* memcpy(eep_write_buf.data, SII_EE_DEFLT, (SII_EE_DEFLT_SIZE < EEP_EMU_BYTES) ? SII_EE_DEFLT_SIZE : EEP_EMU_BYTES);
*/
/* setup header data */
eep_write_buf.header.seq = 0;
eep_write_buf.header.crc = fce_crc32 (&fce_config,
(const uint32_t *)eep_write_buf.data, EEP_DATA_BYTES);
/* write pages */
src = (const uint32_t *) &eep_write_buf;
dst = EEP_SECTOR_A;
for (i = 0; i < EEP_PAGES_PER_BLOCK; i++) {
nor_write(drv, EEP_FLASH_SECTOR_OFFSET(dst), EEP_BYTES_PER_PAGE,
(const uint8_t *)src);
src += (EEP_BYTES_PER_PAGE / sizeof(*src));
dst += EEP_BYTES_PER_PAGE;
}
/* set current block */
eep_curr_block = (eep_block_t *) EEP_SECTOR_A;
}
static void find_latest_block(eep_block_t *addr)
{
uint32_t blk, crc;
for (blk = 0; blk < EPP_BLOCKS_PER_SECT; blk++, addr++) {
/* check crc, skip invalid blocks */
crc = fce_crc32 (&fce_config, (const uint32_t *) addr->data,
EEP_DATA_BYTES);
if (addr->header.crc != crc) {
continue;
}
/* check sequence number and update last pointer */
if (eep_curr_block == NULL || (addr->header.seq - eep_curr_block->header.seq) > 0) {
eep_curr_block = addr;
}
}
}
static eep_block_t *get_next_block(eep_block_t *block)
{
/* simple case: new block fits in current sector */
uint32_t sect_offset = ((uint32_t)block) & (EEP_BYTES_PER_SECTOR - 1);
if ((sect_offset + EEP_BYTES_PER_BLOCK) < EEP_BYTES_PER_SECTOR) {
return block + 1;
}
/* use other sector */
return cleanup_unused_sect(block);
}
static eep_block_t *cleanup_unused_sect(eep_block_t *block)
{
/* get other sector */
uint32_t sect_addr = (((uint32_t)block) & ~(EEP_BYTES_PER_SECTOR - 1));
if (sect_addr == EEP_SECTOR_A) {
sect_addr = EEP_SECTOR_B;
} else {
sect_addr = EEP_SECTOR_A;
}
/* check if sector is empty, erase if not */
if (!is_sector_empty((uint32_t *)sect_addr)) {
nor_erase(drv, EEP_FLASH_SECTOR_OFFSET(sect_addr), EEP_BYTES_PER_SECTOR);
}
return (eep_block_t *) sect_addr;
}
static int32_t is_sector_empty(uint32_t *addr)
{
uint32_t i;
/* check for all bytes erased */
for (i=0; i<EEP_BYTES_PER_SECTOR; i+=sizeof(uint32_t), addr++) {
if (*addr != 0) {
return 0;
}
}
return 1;
}

View File

@ -0,0 +1,54 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* ESC hardware specifoc EEPROM emulation functions.
*/
#ifndef __esc_hw_eep__
#define __esc_hw_eep__
#include <bsp.h>
#include <cc.h>
#include "esc_eep.h"
/* idle timeout in ns before actual flash write will be issued */
#define EEP_IDLE_TIMEOUT 100000000
/* Pages per emulated EEPROM block */
#define EEP_BYTES_PER_SECTOR XMC4_EEPROM_SECTOR_SIZE_BYTES
#define EEP_BYTES_PER_PAGE XMC4_PAGE_SIZE_BYTES
#define EEP_PAGES_PER_BLOCK 16
/* block header */
typedef struct CC_PACKED
{
int32_t seq;
uint32_t crc;
} eep_header_t;
/* calculate resulting sizes */
#define EEP_BYTES_PER_BLOCK (EEP_PAGES_PER_BLOCK * EEP_BYTES_PER_PAGE)
#define EPP_BLOCKS_PER_SECT (EEP_BYTES_PER_SECTOR / EEP_BYTES_PER_BLOCK)
#define EEP_DATA_BYTES (EEP_BYTES_PER_BLOCK - sizeof(eep_header_t))
/* eeprom size increments in steps of 0x80 bytes */
#define EEP_EMU_BYTES (EEP_DATA_BYTES & ~0x7f)
/* block structure */
typedef struct CC_PACKED
{
eep_header_t header;
uint8_t data[EEP_DATA_BYTES];
} eep_block_t;
/* periodic task */
void EEP_hw_process (void);
#endif