#include "fec_ecat.h"#include <dev.h>#include <kern.h>#include <string.h>#include <uassert.h>#include <eth/fec_buffer.h>#include <eth/phy/mii.h>#include <bsp.h>#include <config.h>
Go to the source code of this file.
| Classes | |
| struct | fec | 
| struct | fec_cfg | 
| struct | fec_mac_t | 
| struct | fec_mib | 
| struct | reg_fec | 
| Macros | |
| #define | DELAY(ms) task_delay (tick_from_ms (ms) + 1) | 
| #define | DPRINT(...) | 
| #define | DUMP_PACKET(p, l) | 
| #define | ETH_PHY_ADDRESS 0x1 /* Default jumper setting on TWR-K60F */ | 
| #define | ETHERNET_FCS_SIZE_IN_BYTES 4 /* Frame Check Sequence (32-bit CRC) */ | 
| #define | FEC_ALLIGNED __attribute__((section(".dma"),aligned(16))) | 
| #define | FEC_ECR_DBSWP (0x00000100) | 
| #define | FEC_ECR_ETHER_EN (0x00000002) | 
| #define | FEC_ECR_RESET (0x00000001) | 
| #define | FEC_EIR_BABR (0x40000000) | 
| #define | FEC_EIR_BABT (0x20000000) | 
| #define | FEC_EIR_CLEAR_ALL (0xFFF80000) | 
| #define | FEC_EIR_EBERR (0x00400000) | 
| #define | FEC_EIR_GRA (0x10000000) | 
| #define | FEC_EIR_HBERR (0x80000000) | 
| #define | FEC_EIR_LC (0x00200000) | 
| #define | FEC_EIR_MII (0x00800000) | 
| #define | FEC_EIR_RL (0x00100000) | 
| #define | FEC_EIR_RXB (0x01000000) | 
| #define | FEC_EIR_RXF (0x02000000) | 
| #define | FEC_EIR_TXB (0x04000000) | 
| #define | FEC_EIR_TXF (0x08000000) | 
| #define | FEC_EIR_UN (0x00080000) | 
| #define | FEC_EMRBR_R_BUF_SIZE(x) (((x)&0x7F)<<4) | 
| #define | FEC_ERDSR_R_DES_START(x) (((x)&0x3FFFFFFF)<<2) | 
| #define | FEC_ETDSR_X_DES_START(x) (((x)&0x3FFFFFFF)<<2) | 
| #define | FEC_FRBR_R_BOUND(x) (((x)&0xFF)<<2) | 
| #define | FEC_FRSR_R_FSTART(x) (((x)&0xFF)<<2) | 
| #define | FEC_MIBC_MIB_DISABLE (0x80000000) | 
| #define | FEC_MIBC_MIB_IDLE (0x40000000) | 
| #define | FEC_MII_DATA_MASK 0x0000FFFF | 
| #define | FEC_MII_DATA_OFF 0 | 
| #define | FEC_MII_FRAME (FEC_MII_ST | FEC_MII_TA) | 
| #define | FEC_MII_GET_DATA(v) (((v) >> FEC_MII_DATA_OFF) & FEC_MII_DATA_MASK) | 
| #define | FEC_MII_OP(x) (((x) & FEC_MII_OP_MASK) << FEC_MII_OP_OFF) | 
| #define | FEC_MII_OP_MASK 0x03 | 
| #define | FEC_MII_OP_OFF 28 | 
| #define | FEC_MII_OP_RD 0x02 | 
| #define | FEC_MII_OP_WR 0x01 | 
| #define | FEC_MII_PA(pa) (((pa) & FEC_MII_PA_MASK) << FEC_MII_PA_OFF) | 
| #define | FEC_MII_PA_MASK 0xFF | 
| #define | FEC_MII_PA_OFF 23 | 
| #define | FEC_MII_RA(ra) (((ra) & FEC_MII_RA_MASK) << FEC_MII_RA_OFF) | 
| #define | FEC_MII_RA_MASK 0xFF | 
| #define | FEC_MII_RA_OFF 18 | 
| #define | FEC_MII_READ(pa, ra) | 
| #define | FEC_MII_SET_DATA(v) (((v) & FEC_MII_DATA_MASK) << FEC_MII_DATA_OFF) | 
| #define | FEC_MII_ST 0x40000000 | 
| #define | FEC_MII_TA 0x00020000 | 
| #define | FEC_MII_TICK 1 | 
| #define | FEC_MII_TIMEOUT 10 | 
| #define | FEC_MII_WRITE(pa, ra, v) | 
| #define | FEC_MIN_MODULE_CLOCK_Hz (25 * 1000 * 1000) | 
| #define | FEC_MMFR_DATA(x) (((x)&0xFFFF)) | 
| #define | FEC_MMFR_OP_RD (0x20000000) | 
| #define | FEC_MMFR_OP_WR (0x10000000) | 
| #define | FEC_MMFR_PA(x) (((x)&0x1F)<<23) | 
| #define | FEC_MMFR_RA(x) (((x)&0x1F)<<18) | 
| #define | FEC_MMFR_ST(x) (((x)&0x03)<<30) | 
| #define | FEC_MMFR_ST_01 (0x40000000) | 
| #define | FEC_MMFR_TA(x) (((x)&0x03)<<16) | 
| #define | FEC_MMFR_TA_10 (0x00020000) | 
| #define | FEC_MODULE_CLOCK_Hz CFG_IPG_CLOCK | 
| #define | FEC_MSCR_DIS_PREAMBLE (0x00000080) | 
| #define | FEC_MSCR_MII_SPEED(x) (((x)&0x3F)<<1) | 
| #define | FEC_OPD_OPCODE(x) (((x)&0x0000FFFF)<<16) | 
| #define | FEC_OPD_PAUSE_DUR(x) (((x)&0x0000FFFF)<<0) | 
| #define | FEC_PAUR_PADDR2(x) (((x)&0xFFFF)<<16) | 
| #define | FEC_PAUR_TYPE(x) ((x)&0xFFFF) | 
| #define | FEC_RCR_BC_REJ (0x00000010) | 
| #define | FEC_RCR_CNTL_FRM_ENA (0x00008000) | 
| #define | FEC_RCR_CRC_FWD (0x00004000) | 
| #define | FEC_RCR_DRT (0x00000002) | 
| #define | FEC_RCR_FCE (0x00000020) | 
| #define | FEC_RCR_GRS (0x80000000) | 
| #define | FEC_RCR_LOOP (0x00000001) | 
| #define | FEC_RCR_MAX_FL(x) (((x)&0x7FF)<<16) | 
| #define | FEC_RCR_MII_MODE (0x00000004) | 
| #define | FEC_RCR_NO_LGTH_CHECK (0x40000000) | 
| #define | FEC_RCR_PAD_EN (0x00001000) | 
| #define | FEC_RCR_PAUSE_FWD (0x00002000) | 
| #define | FEC_RCR_PROM (0x00000008) | 
| #define | FEC_RCR_RGMII_ENA (0x00000040) | 
| #define | FEC_RCR_RMII_10T (0x00000200) | 
| #define | FEC_RCR_RMII_ECHO (0x00000800) | 
| #define | FEC_RCR_RMII_LOOP (0x00000400) | 
| #define | FEC_RCR_RMII_MODE (0x00000100) | 
| #define | FEC_RCR_SGMII_ENA (0x00000080) | 
| #define | FEC_RDAR_R_DES_ACTIVE (0x01000000) | 
| #define | FEC_TCR_FDEN (0x00000004) | 
| #define | FEC_TCR_GTS (0x00000001) | 
| #define | FEC_TCR_HBC (0x00000002) | 
| #define | FEC_TCR_RFC_PAUSE (0x00000010) | 
| #define | FEC_TCR_TFC_PAUSE (0x00000008) | 
| #define | FEC_TDAR_X_DES_ACTIVE (0x01000000) | 
| #define | FEC_TFWR_STR_FWD BIT (8) /* Present on ENET but not on FEC */ | 
| #define | FEC_TFWR_X_WMRK(x) ((x)&0x03) | 
| #define | FEC_TFWR_X_WMRK_128 (0x02) | 
| #define | FEC_TFWR_X_WMRK_192 (0x03) | 
| #define | FEC_TFWR_X_WMRK_64 (0x01) | 
| #define | NUM_BUFFERS 2 | 
| #define | PKT_MAXBUF_SIZE 1518 | 
| Typedefs | |
| typedef struct fec_cfg | fec_cfg_t | 
| typedef struct fec_mac_t | fec_mac_t | 
| typedef struct fec_mib | fec_mib_t | 
| typedef enum fec_phy_inteface | fec_phy_inteface_t | 
| typedef struct fec | fec_t | 
| typedef struct reg_fec | reg_fec_t | 
| Enumerations | |
| enum | fec_phy_inteface { FEC_PHY_MII, FEC_PHY_RMII, FEC_PHY_RGMII } | 
| Functions | |
| COMPILETIME_ASSERT (sizeof(fec_mib_t)==0x100) | |
| COMPILETIME_ASSERT (offsetof(reg_fec_t, emrbr)==0x188) | |
| COMPILETIME_ASSERT (offsetof(reg_fec_t, tx_almost_full)==0x1A8) | |
| COMPILETIME_ASSERT (offsetof(reg_fec_t, fec_miigsk_cfgr)==0x300) | |
| COMPILETIME_ASSERT (offsetof(reg_fec_t, smac)==0x500) | |
| COMPILETIME_ASSERT (offsetof(reg_fec_t, smac[3])==0x518) | |
| COMPILETIME_ASSERT (FEC_MODULE_CLOCK_Hz >=FEC_MIN_MODULE_CLOCK_Hz) | |
| static void | fec_ecat_hotplug (void) | 
| int | fec_ecat_init (const fec_mac_address_t *mac_address, bool phy_loopback_mode) | 
| static void | fec_ecat_init_hw (const fec_mac_address_t *mac_address) | 
| static dev_state_t | fec_ecat_probe (void) | 
| static uint16_t | fec_ecat_read_phy (void *arg, uint8_t address, uint8_t reg) | 
| int | fec_ecat_recv (void *buffer, size_t buffer_length) | 
| int | fec_ecat_send (const void *payload, size_t tot_len) | 
| static void | fec_ecat_write_phy (void *arg, uint8_t address, uint8_t reg, uint16_t value) | 
| Variables | |
| static fec_t * | fec | 
| static fec_buffer_bd_t fec_tx_bd[NUM_BUFFERS] | FEC_ALLIGNED | 
| #define DELAY | ( | ms | ) | task_delay (tick_from_ms (ms) + 1) | 
Definition at line 49 of file fec_ecat.c.
| #define DPRINT | ( | ... | ) | 
Definition at line 38 of file fec_ecat.c.
| #define DUMP_PACKET | ( | p, | |
| l | |||
| ) | 
Definition at line 44 of file fec_ecat.c.
| #define ETH_PHY_ADDRESS 0x1 /* Default jumper setting on TWR-K60F */ | 
Definition at line 51 of file fec_ecat.c.
| #define ETHERNET_FCS_SIZE_IN_BYTES 4 /* Frame Check Sequence (32-bit CRC) */ | 
Definition at line 47 of file fec_ecat.c.
| #define FEC_ALLIGNED __attribute__((section(".dma"),aligned(16))) | 
Definition at line 54 of file fec_ecat.c.
| #define FEC_ECR_DBSWP (0x00000100) | 
Definition at line 225 of file fec_ecat.c.
| #define FEC_ECR_ETHER_EN (0x00000002) | 
Definition at line 226 of file fec_ecat.c.
| #define FEC_ECR_RESET (0x00000001) | 
Definition at line 227 of file fec_ecat.c.
| #define FEC_EIR_BABR (0x40000000) | 
Definition at line 205 of file fec_ecat.c.
| #define FEC_EIR_BABT (0x20000000) | 
Definition at line 206 of file fec_ecat.c.
| #define FEC_EIR_CLEAR_ALL (0xFFF80000) | 
Definition at line 203 of file fec_ecat.c.
| #define FEC_EIR_EBERR (0x00400000) | 
Definition at line 213 of file fec_ecat.c.
| #define FEC_EIR_GRA (0x10000000) | 
Definition at line 207 of file fec_ecat.c.
| #define FEC_EIR_HBERR (0x80000000) | 
Definition at line 204 of file fec_ecat.c.
| #define FEC_EIR_LC (0x00200000) | 
Definition at line 214 of file fec_ecat.c.
| #define FEC_EIR_MII (0x00800000) | 
Definition at line 212 of file fec_ecat.c.
| #define FEC_EIR_RL (0x00100000) | 
Definition at line 215 of file fec_ecat.c.
| #define FEC_EIR_RXB (0x01000000) | 
Definition at line 211 of file fec_ecat.c.
| #define FEC_EIR_RXF (0x02000000) | 
Definition at line 210 of file fec_ecat.c.
| #define FEC_EIR_TXB (0x04000000) | 
Definition at line 209 of file fec_ecat.c.
| #define FEC_EIR_TXF (0x08000000) | 
Definition at line 208 of file fec_ecat.c.
| #define FEC_EIR_UN (0x00080000) | 
Definition at line 216 of file fec_ecat.c.
| #define FEC_EMRBR_R_BUF_SIZE | ( | x | ) | (((x)&0x7F)<<4) | 
Definition at line 304 of file fec_ecat.c.
| #define FEC_ERDSR_R_DES_START | ( | x | ) | (((x)&0x3FFFFFFF)<<2) | 
Definition at line 298 of file fec_ecat.c.
| #define FEC_ETDSR_X_DES_START | ( | x | ) | (((x)&0x3FFFFFFF)<<2) | 
Definition at line 301 of file fec_ecat.c.
| #define FEC_FRBR_R_BOUND | ( | x | ) | (((x)&0xFF)<<2) | 
Definition at line 292 of file fec_ecat.c.
| #define FEC_FRSR_R_FSTART | ( | x | ) | (((x)&0xFF)<<2) | 
Definition at line 295 of file fec_ecat.c.
| #define FEC_MIBC_MIB_DISABLE (0x80000000) | 
Definition at line 245 of file fec_ecat.c.
| #define FEC_MIBC_MIB_IDLE (0x40000000) | 
Definition at line 246 of file fec_ecat.c.
| #define FEC_MII_DATA_MASK 0x0000FFFF | 
Definition at line 320 of file fec_ecat.c.
| #define FEC_MII_DATA_OFF 0 | 
Definition at line 319 of file fec_ecat.c.
| #define FEC_MII_FRAME (FEC_MII_ST | FEC_MII_TA) | 
Definition at line 322 of file fec_ecat.c.
| #define FEC_MII_GET_DATA | ( | v | ) | (((v) >> FEC_MII_DATA_OFF) & FEC_MII_DATA_MASK) | 
Definition at line 327 of file fec_ecat.c.
| #define FEC_MII_OP | ( | x | ) | (((x) & FEC_MII_OP_MASK) << FEC_MII_OP_OFF) | 
Definition at line 323 of file fec_ecat.c.
| #define FEC_MII_OP_MASK 0x03 | 
Definition at line 311 of file fec_ecat.c.
| #define FEC_MII_OP_OFF 28 | 
Definition at line 310 of file fec_ecat.c.
| #define FEC_MII_OP_RD 0x02 | 
Definition at line 312 of file fec_ecat.c.
| #define FEC_MII_OP_WR 0x01 | 
Definition at line 313 of file fec_ecat.c.
| #define FEC_MII_PA | ( | pa | ) | (((pa) & FEC_MII_PA_MASK) << FEC_MII_PA_OFF) | 
Definition at line 324 of file fec_ecat.c.
| #define FEC_MII_PA_MASK 0xFF | 
Definition at line 315 of file fec_ecat.c.
| #define FEC_MII_PA_OFF 23 | 
Definition at line 314 of file fec_ecat.c.
| #define FEC_MII_RA | ( | ra | ) | (((ra) & FEC_MII_RA_MASK) << FEC_MII_RA_OFF) | 
Definition at line 325 of file fec_ecat.c.
| #define FEC_MII_RA_MASK 0xFF | 
Definition at line 317 of file fec_ecat.c.
| #define FEC_MII_RA_OFF 18 | 
Definition at line 316 of file fec_ecat.c.
| #define FEC_MII_READ | ( | pa, | |
| ra | |||
| ) | 
Definition at line 328 of file fec_ecat.c.
| #define FEC_MII_SET_DATA | ( | v | ) | (((v) & FEC_MII_DATA_MASK) << FEC_MII_DATA_OFF) | 
Definition at line 326 of file fec_ecat.c.
| #define FEC_MII_ST 0x40000000 | 
Definition at line 309 of file fec_ecat.c.
| #define FEC_MII_TA 0x00020000 | 
Definition at line 318 of file fec_ecat.c.
| #define FEC_MII_TICK 1 | 
Definition at line 334 of file fec_ecat.c.
| #define FEC_MII_TIMEOUT 10 | 
Definition at line 333 of file fec_ecat.c.
| #define FEC_MII_WRITE | ( | pa, | |
| ra, | |||
| v | |||
| ) | 
Definition at line 330 of file fec_ecat.c.
| #define FEC_MIN_MODULE_CLOCK_Hz (25 * 1000 * 1000) | 
Definition at line 63 of file fec_ecat.c.
| #define FEC_MMFR_DATA | ( | x | ) | (((x)&0xFFFF)) | 
Definition at line 230 of file fec_ecat.c.
| #define FEC_MMFR_OP_RD (0x20000000) | 
Definition at line 233 of file fec_ecat.c.
| #define FEC_MMFR_OP_WR (0x10000000) | 
Definition at line 234 of file fec_ecat.c.
| #define FEC_MMFR_PA | ( | x | ) | (((x)&0x1F)<<23) | 
Definition at line 235 of file fec_ecat.c.
| #define FEC_MMFR_RA | ( | x | ) | (((x)&0x1F)<<18) | 
Definition at line 236 of file fec_ecat.c.
| #define FEC_MMFR_ST | ( | x | ) | (((x)&0x03)<<30) | 
Definition at line 231 of file fec_ecat.c.
| #define FEC_MMFR_ST_01 (0x40000000) | 
Definition at line 232 of file fec_ecat.c.
| #define FEC_MMFR_TA | ( | x | ) | (((x)&0x03)<<16) | 
Definition at line 237 of file fec_ecat.c.
| #define FEC_MMFR_TA_10 (0x00020000) | 
Definition at line 238 of file fec_ecat.c.
| #define FEC_MODULE_CLOCK_Hz CFG_IPG_CLOCK | 
Definition at line 66 of file fec_ecat.c.
| #define FEC_MSCR_DIS_PREAMBLE (0x00000080) | 
Definition at line 241 of file fec_ecat.c.
| #define FEC_MSCR_MII_SPEED | ( | x | ) | (((x)&0x3F)<<1) | 
Definition at line 242 of file fec_ecat.c.
| #define FEC_OPD_OPCODE | ( | x | ) | (((x)&0x0000FFFF)<<16) | 
Definition at line 282 of file fec_ecat.c.
| #define FEC_OPD_PAUSE_DUR | ( | x | ) | (((x)&0x0000FFFF)<<0) | 
Definition at line 281 of file fec_ecat.c.
| #define FEC_PAUR_PADDR2 | ( | x | ) | (((x)&0xFFFF)<<16) | 
Definition at line 277 of file fec_ecat.c.
| #define FEC_PAUR_TYPE | ( | x | ) | ((x)&0xFFFF) | 
Definition at line 278 of file fec_ecat.c.
| #define FEC_RCR_BC_REJ (0x00000010) | 
Definition at line 263 of file fec_ecat.c.
| #define FEC_RCR_CNTL_FRM_ENA (0x00008000) | 
Definition at line 252 of file fec_ecat.c.
| #define FEC_RCR_CRC_FWD (0x00004000) | 
Definition at line 253 of file fec_ecat.c.
| #define FEC_RCR_DRT (0x00000002) | 
Definition at line 266 of file fec_ecat.c.
| #define FEC_RCR_FCE (0x00000020) | 
Definition at line 262 of file fec_ecat.c.
| #define FEC_RCR_GRS (0x80000000) | 
Definition at line 249 of file fec_ecat.c.
| #define FEC_RCR_LOOP (0x00000001) | 
Definition at line 267 of file fec_ecat.c.
| #define FEC_RCR_MAX_FL | ( | x | ) | (((x)&0x7FF)<<16) | 
Definition at line 251 of file fec_ecat.c.
| #define FEC_RCR_MII_MODE (0x00000004) | 
Definition at line 265 of file fec_ecat.c.
| #define FEC_RCR_NO_LGTH_CHECK (0x40000000) | 
Definition at line 250 of file fec_ecat.c.
| #define FEC_RCR_PAD_EN (0x00001000) | 
Definition at line 255 of file fec_ecat.c.
| #define FEC_RCR_PAUSE_FWD (0x00002000) | 
Definition at line 254 of file fec_ecat.c.
| #define FEC_RCR_PROM (0x00000008) | 
Definition at line 264 of file fec_ecat.c.
| #define FEC_RCR_RGMII_ENA (0x00000040) | 
Definition at line 261 of file fec_ecat.c.
| #define FEC_RCR_RMII_10T (0x00000200) | 
Definition at line 258 of file fec_ecat.c.
| #define FEC_RCR_RMII_ECHO (0x00000800) | 
Definition at line 256 of file fec_ecat.c.
| #define FEC_RCR_RMII_LOOP (0x00000400) | 
Definition at line 257 of file fec_ecat.c.
| #define FEC_RCR_RMII_MODE (0x00000100) | 
Definition at line 259 of file fec_ecat.c.
| #define FEC_RCR_SGMII_ENA (0x00000080) | 
Definition at line 260 of file fec_ecat.c.
| #define FEC_RDAR_R_DES_ACTIVE (0x01000000) | 
Definition at line 219 of file fec_ecat.c.
| #define FEC_TCR_FDEN (0x00000004) | 
Definition at line 272 of file fec_ecat.c.
| #define FEC_TCR_GTS (0x00000001) | 
Definition at line 274 of file fec_ecat.c.
| #define FEC_TCR_HBC (0x00000002) | 
Definition at line 273 of file fec_ecat.c.
| #define FEC_TCR_RFC_PAUSE (0x00000010) | 
Definition at line 270 of file fec_ecat.c.
| #define FEC_TCR_TFC_PAUSE (0x00000008) | 
Definition at line 271 of file fec_ecat.c.
| #define FEC_TDAR_X_DES_ACTIVE (0x01000000) | 
Definition at line 222 of file fec_ecat.c.
| #define FEC_TFWR_STR_FWD BIT (8) /* Present on ENET but not on FEC */ | 
Definition at line 285 of file fec_ecat.c.
| #define FEC_TFWR_X_WMRK | ( | x | ) | ((x)&0x03) | 
Definition at line 286 of file fec_ecat.c.
| #define FEC_TFWR_X_WMRK_128 (0x02) | 
Definition at line 288 of file fec_ecat.c.
| #define FEC_TFWR_X_WMRK_192 (0x03) | 
Definition at line 289 of file fec_ecat.c.
| #define FEC_TFWR_X_WMRK_64 (0x01) | 
Definition at line 287 of file fec_ecat.c.
| #define NUM_BUFFERS 2 | 
Definition at line 53 of file fec_ecat.c.
| #define PKT_MAXBUF_SIZE 1518 | 
Definition at line 339 of file fec_ecat.c.
| typedef enum fec_phy_inteface fec_phy_inteface_t | 
| enum fec_phy_inteface | 
| Enumerator | |
|---|---|
| FEC_PHY_MII | MII, Media Independent Interface 4-bit operating at 25 Mhz | 
| FEC_PHY_RMII | RMII, Reduced Media Independent Interface 2-bit operating at 50 Mhz | 
| FEC_PHY_RGMII | |
Definition at line 343 of file fec_ecat.c.
| COMPILETIME_ASSERT | ( | sizeof(fec_mib_t) | = =0x100 | ) | 
| COMPILETIME_ASSERT | ( | offsetof(reg_fec_t, emrbr) | = =0x188 | ) | 
| COMPILETIME_ASSERT | ( | offsetof(reg_fec_t, tx_almost_full) | = =0x1A8 | ) | 
| COMPILETIME_ASSERT | ( | offsetof(reg_fec_t, fec_miigsk_cfgr) | = =0x300 | ) | 
| COMPILETIME_ASSERT | ( | offsetof(reg_fec_t, smac) | = =0x500 | ) | 
| COMPILETIME_ASSERT | ( | offsetof(reg_fec_t, smac[3]) | = =0x518 | ) | 
| COMPILETIME_ASSERT | ( | FEC_MODULE_CLOCK_Hz >= | FEC_MIN_MODULE_CLOCK_Hz | ) | 
| 
 | static | 
Definition at line 666 of file fec_ecat.c.
| 
 | static | 
Definition at line 501 of file fec_ecat.c.
| 
 | static | 
Definition at line 742 of file fec_ecat.c.
Definition at line 476 of file fec_ecat.c.
Definition at line 489 of file fec_ecat.c.
Definition at line 385 of file fec_ecat.c.
| 
 | static | 
Definition at line 378 of file fec_ecat.c.