Update EoE application to new SOES version
parent
14397b0575
commit
54de5af4b5
|
@ -1,10 +1,16 @@
|
|||
#ifndef __CONFIG_H__
|
||||
#define __CONFIG_H__
|
||||
#ifndef __ECAT_OPTIONS_H__
|
||||
#define __ECAT_OPTIONS_H__
|
||||
|
||||
#include <cc.h>
|
||||
#include "cc.h"
|
||||
|
||||
#define USE_FOE 0
|
||||
#define USE_EOE 1
|
||||
|
||||
#define MAX_INPUT_SIZE 128
|
||||
#define MAX_OUTPUT_SIZE 128
|
||||
|
||||
#define MBXSIZE 128
|
||||
#define MBXSIZEBOOT 256
|
||||
#define MBXSIZEBOOT 128
|
||||
#define MBXBUFFERS 3
|
||||
|
||||
#define MBX0_sma 0x1000
|
||||
|
@ -26,10 +32,13 @@
|
|||
#define MBX1_smc_b 0x22
|
||||
|
||||
#define SM2_sma 0x1100
|
||||
#define SM2_smc 0x24
|
||||
#define SM2_smc 0x64
|
||||
#define SM2_act 1
|
||||
#define SM3_sma 0x1180
|
||||
#define SM3_smc 0x20
|
||||
#define SM3_act 1
|
||||
|
||||
#endif /* __CONFIG_H__ */
|
||||
#define MAX_MAPPINGS_SM2 2
|
||||
#define MAX_MAPPINGS_SM3 1
|
||||
|
||||
#endif /* __ECAT_OPTIONS_H__ */
|
|
@ -1,312 +0,0 @@
|
|||
/*
|
||||
* 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(ESCvar.dcsync == 0)
|
||||
{
|
||||
DIG_process(DIG_PROCESS_OUTPUTS_FLAG | DIG_PROCESS_APP_HOOK_FLAG |
|
||||
DIG_PROCESS_INPUTS_FLAG);
|
||||
}
|
||||
else
|
||||
{
|
||||
DIG_process(DIG_PROCESS_OUTPUTS_FLAG);
|
||||
}
|
||||
}
|
||||
|
||||
#if 1
|
||||
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);
|
||||
|
||||
extern flags_t * ecat_events;
|
||||
flags_set(ecat_events, EVENT_ISR);
|
||||
//sem_signal(ecat_isr_sem);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if 0
|
||||
/* Function for PDI ISR serving task */
|
||||
static void isr_run(void * arg)
|
||||
{
|
||||
while(1)
|
||||
{
|
||||
sem_wait(ecat_isr_sem);
|
||||
ecat_slv_worker(ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
|
||||
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
/** 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 = 0;
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -1,179 +0,0 @@
|
|||
/*
|
||||
* 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] ================ */
|
||||
/* ================================================================================ */
|
||||
|
||||
#define EVENT_PERIODIC BIT(0)
|
||||
#define EVENT_TX BIT(1)
|
||||
#define EVENT_ISR BIT(2)
|
||||
|
||||
|
||||
/**
|
||||
* @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
|
||||
|
|
@ -1,311 +0,0 @@
|
|||
/*
|
||||
* 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;
|
||||
}
|
||||
|
||||
|
|
@ -1,54 +0,0 @@
|
|||
/*
|
||||
* 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
|
||||
|
||||
|
|
@ -1,19 +1,22 @@
|
|||
|
||||
#include <kern.h>
|
||||
#include <xmc4.h>
|
||||
#include <bsp.h>
|
||||
#include "esc.h"
|
||||
#include "esc_eoe.h"
|
||||
#include "slave.h"
|
||||
#include "esc_hw.h"
|
||||
#include "config.h"
|
||||
|
||||
#include "ecat_slv.h"
|
||||
#include "options.h"
|
||||
#include "utypes.h"
|
||||
#include <lwip/sys.h>
|
||||
#include <lwip/netifapi.h>
|
||||
#include <netif/etharp.h>
|
||||
#include <string.h>
|
||||
|
||||
#define CFG_HOSTNAME "xmc48relax"
|
||||
|
||||
static struct netif * found_if;
|
||||
static mbox_t * pbuf_mbox;
|
||||
static tmr_t * ecat_timer;
|
||||
static uint8_t mac_address[6] = {0x1E, 0x30, 0x6C, 0xA2, 0x45, 0x5E};
|
||||
|
||||
static void appl_get_buffer (eoe_pbuf_t * ebuf);
|
||||
|
@ -23,88 +26,69 @@ static int appl_store_ethernet_settings (void);
|
|||
static void appl_handle_recv_buffer (uint8_t port, eoe_pbuf_t * ebuf);
|
||||
static int appl_fetch_send_buffer (uint8_t port, eoe_pbuf_t * ebuf);
|
||||
|
||||
flags_t * ecat_events;
|
||||
/* Application variables */
|
||||
_Objects Obj;
|
||||
|
||||
/**
|
||||
* This function gets input values and updates Rb.Button1
|
||||
*/
|
||||
void cb_get_Button1()
|
||||
extern sem_t * ecat_isr_sem;
|
||||
|
||||
struct netif * net_add_interface (err_t (*netif_fn) (struct netif * netif))
|
||||
{
|
||||
Rb.Button1.B = gpio_get(GPIO_BUTTON1);
|
||||
struct netif * netif;
|
||||
ip_addr_t ipaddr;
|
||||
ip_addr_t netmask;
|
||||
ip_addr_t gateway;
|
||||
err_enum_t error;
|
||||
|
||||
netif = malloc (sizeof(struct netif));
|
||||
UASSERT (netif != NULL, EMEM);
|
||||
|
||||
/* Set default (zero) values */
|
||||
ip_addr_set_zero (&ipaddr);
|
||||
ip_addr_set_zero (&netmask);
|
||||
ip_addr_set_zero (&gateway);
|
||||
|
||||
/* Let lwIP TCP/IP thread initialise and add the interface. The interface
|
||||
* will be down until net_configure() is called.
|
||||
*/
|
||||
error = netifapi_netif_add (
|
||||
netif, &ipaddr, &netmask, &gateway, NULL, netif_fn, tcpip_input);
|
||||
UASSERT (error == ERR_OK, EARG);
|
||||
|
||||
return netif;
|
||||
}
|
||||
|
||||
/**
|
||||
* This function gets input values and updates Rb.Button2
|
||||
*/
|
||||
void cb_get_Button2()
|
||||
void cb_get_inputs (void)
|
||||
{
|
||||
Rb.Button2.B = gpio_get(GPIO_BUTTON2);
|
||||
static int count;
|
||||
Obj.Buttons.Button1 = gpio_get(GPIO_BUTTON1);
|
||||
if(Obj.Buttons.Button1 == 0)
|
||||
{
|
||||
count++;
|
||||
if(count > 1000)
|
||||
{
|
||||
ESC_ALstatusgotoerror((ESCsafeop | ESCerror), ALERR_WATCHDOG);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
count = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup1
|
||||
*/
|
||||
void cb_set_LEDgroup1()
|
||||
void cb_set_outputs (void)
|
||||
{
|
||||
gpio_set(GPIO_LED1_B, Wb.LEDgroup1.LED);
|
||||
gpio_set(GPIO_LED1, Obj.LEDgroup0.LED0);
|
||||
gpio_set(GPIO_LED2, Obj.LEDgroup1.LED1);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup2
|
||||
*/
|
||||
void cb_set_LEDgroup2()
|
||||
void cb_state_change (uint8_t * as, uint8_t * an)
|
||||
{
|
||||
gpio_set(GPIO_LED2_B, Wb.LEDgroup2.LED);
|
||||
}
|
||||
if (*as == SAFEOP_TO_OP)
|
||||
{
|
||||
/* Enable watchdog interrupt */
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | ESCREG_ALEVENT_WD);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup3
|
||||
*/
|
||||
void cb_set_LEDgroup3()
|
||||
{
|
||||
gpio_set(GPIO_LED3_B, Wb.LEDgroup3.LED);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup4
|
||||
*/
|
||||
void cb_set_LEDgroup4()
|
||||
{
|
||||
gpio_set(GPIO_LED4_B, Wb.LEDgroup4.LED);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup5
|
||||
*/
|
||||
void cb_set_LEDgroup5()
|
||||
{
|
||||
gpio_set(GPIO_LED5_B, Wb.LEDgroup5.LED5);
|
||||
gpio_set(GPIO_LED6_B, Wb.LEDgroup5.LED678 & 0x1);
|
||||
gpio_set(GPIO_LED7_B, Wb.LEDgroup5.LED678 & 0x2);
|
||||
gpio_set(GPIO_LED8_B, Wb.LEDgroup5.LED678 & 0x4);
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called after a SDO write of the object Cb.Parameters.
|
||||
*/
|
||||
void cb_post_write_Parameters(int subindex)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called after a SDO write of the object Cb.variableRW.
|
||||
*/
|
||||
void cb_post_write_variableRW(int subindex)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/** Optional: Hook called after state change for application specific
|
||||
* actions for specific state changes.
|
||||
*/
|
||||
void pre_state_change_hook (uint8_t * as, uint8_t * an)
|
||||
{
|
||||
/* Clean up data if we have been in INIT state */
|
||||
if ((*as == INIT_TO_PREOP) && (*an == ESCinit))
|
||||
{
|
||||
|
@ -123,50 +107,6 @@ void pre_state_change_hook (uint8_t * as, uint8_t * an)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
/* Configuration parameters for EoE
|
||||
* Function callbacks to interact with an TCP/IP stack
|
||||
*/
|
||||
static eoe_cfg_t eoe_config =
|
||||
{
|
||||
.get_buffer = appl_get_buffer,
|
||||
.free_buffer = appl_free_buffer,
|
||||
.load_eth_settings = appl_load_eth_settings,
|
||||
.store_ethernet_settings = appl_store_ethernet_settings,
|
||||
.handle_recv_buffer = appl_handle_recv_buffer,
|
||||
.fetch_send_buffer = appl_fetch_send_buffer,
|
||||
};
|
||||
/* Configuration parameters for SOES
|
||||
* SM and Mailbox parameters comes from the
|
||||
* generated config.h
|
||||
*/
|
||||
static esc_cfg_t config =
|
||||
{
|
||||
.user_arg = NULL,
|
||||
.use_interrupt = 1,
|
||||
.watchdog_cnt = 1000,
|
||||
.mbxsize = MBXSIZE,
|
||||
.mbxsizeboot = MBXSIZEBOOT,
|
||||
.mbxbuffers = MBXBUFFERS,
|
||||
.mb[0] = {MBX0_sma, MBX0_sml, MBX0_sme, MBX0_smc, 0},
|
||||
.mb[1] = {MBX1_sma, MBX1_sml, MBX1_sme, MBX1_smc, 0},
|
||||
.mb_boot[0] = {MBX0_sma_b, MBX0_sml_b, MBX0_sme_b, MBX0_smc_b, 0},
|
||||
.mb_boot[1] = {MBX1_sma_b, MBX1_sml_b, MBX1_sme_b, MBX1_smc_b, 0},
|
||||
.pdosm[0] = {SM2_sma, 0, 0, SM2_smc, SM2_act},
|
||||
.pdosm[1] = {SM3_sma, 0, 0, SM3_smc, SM3_act},
|
||||
.pre_state_change_hook = pre_state_change_hook,
|
||||
.post_state_change_hook = NULL,
|
||||
.application_hook = NULL,
|
||||
.safeoutput_override = NULL,
|
||||
.pre_object_download_hook = NULL,
|
||||
.post_object_download_hook = NULL,
|
||||
.rxpdo_override = NULL,
|
||||
.txpdo_override = NULL,
|
||||
.esc_hw_interrupt_enable = ESC_interrupt_enable,
|
||||
.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
.esc_hw_eep_handler = ESC_eep_handler
|
||||
};
|
||||
|
||||
/* Callback to allocate a buffer */
|
||||
static void appl_get_buffer (eoe_pbuf_t * ebuf)
|
||||
{
|
||||
|
@ -281,7 +221,7 @@ static void appl_handle_recv_buffer (uint8_t port, eoe_pbuf_t * ebuf)
|
|||
}
|
||||
else
|
||||
{
|
||||
flags_set(ecat_events, EVENT_TX);
|
||||
sem_signal(ecat_isr_sem);
|
||||
}
|
||||
}
|
||||
/* Normal procedure to pass the Ethernet frame to lwIP to handle */
|
||||
|
@ -332,7 +272,7 @@ static err_t transmit_frame (struct netif *netif, struct pbuf *p)
|
|||
{
|
||||
/* Create a pbuf ref to keep the buf alive until it is sent over EoE */
|
||||
pbuf_ref(p);
|
||||
flags_set(ecat_events, EVENT_TX);
|
||||
sem_signal(ecat_isr_sem);
|
||||
}
|
||||
return ERR_OK;
|
||||
}
|
||||
|
@ -355,27 +295,54 @@ err_t eoe_netif_init (struct netif * netif)
|
|||
return ERR_OK;
|
||||
}
|
||||
|
||||
/* Periodic EtherCAT timer */
|
||||
static void soes_timer (tmr_t * timer, void * arg)
|
||||
/* Callback on fragment sent event, we trigger a stack cycle to handle mailbox traffic
|
||||
* if we might have more fragements in queue.
|
||||
*/
|
||||
void eoe_frame_sent (void)
|
||||
{
|
||||
flags_t * ev = arg;
|
||||
flags_set(ev, EVENT_PERIODIC);
|
||||
sem_signal(ecat_isr_sem);
|
||||
}
|
||||
|
||||
/* Main EtherCAT loop */
|
||||
void main_run(void * arg)
|
||||
int main (void)
|
||||
{
|
||||
uint32_t mask = EVENT_ISR | EVENT_TX | EVENT_PERIODIC;
|
||||
uint32_t flags;
|
||||
static esc_cfg_t config =
|
||||
{
|
||||
.user_arg = NULL,
|
||||
.use_interrupt = 1,
|
||||
.watchdog_cnt = INT32_MAX, /* Use HW SM watchdog instead */
|
||||
.set_defaults_hook = NULL,
|
||||
.pre_state_change_hook = NULL,
|
||||
.post_state_change_hook = cb_state_change,
|
||||
.application_hook = NULL,
|
||||
.safeoutput_override = NULL,
|
||||
.pre_object_download_hook = NULL,
|
||||
.post_object_download_hook = NULL,
|
||||
.rxpdo_override = NULL,
|
||||
.txpdo_override = NULL,
|
||||
.esc_hw_interrupt_enable = ESC_interrupt_enable,
|
||||
.esc_hw_interrupt_disable = ESC_interrupt_disable,
|
||||
.esc_hw_eep_handler = ESC_eep_handler,
|
||||
.esc_check_dc_handler = NULL
|
||||
};
|
||||
|
||||
/* Configuration parameters for EoE
|
||||
* Function callbacks to interact with an TCP/IP stack
|
||||
*/
|
||||
static eoe_cfg_t eoe_config =
|
||||
{
|
||||
.get_buffer = appl_get_buffer,
|
||||
.free_buffer = appl_free_buffer,
|
||||
.load_eth_settings = appl_load_eth_settings,
|
||||
.store_ethernet_settings = appl_store_ethernet_settings,
|
||||
.handle_recv_buffer = appl_handle_recv_buffer,
|
||||
.fetch_send_buffer = appl_fetch_send_buffer,
|
||||
.fragment_sent_event = eoe_frame_sent,
|
||||
};
|
||||
|
||||
/* Create an mailbox for interprocess communication between TCP/IP stack and
|
||||
* EtherCAT stack.
|
||||
*/
|
||||
pbuf_mbox = mbox_create (10);
|
||||
/* Create periodic events to run the EtherCAT stack and application */
|
||||
ecat_events = flags_create (0);
|
||||
ecat_timer = tmr_create (tick_from_ms (1), soes_timer, ecat_events, TMR_CYCL);
|
||||
tmr_start (ecat_timer);
|
||||
/* Set up dummy IF */
|
||||
found_if = net_add_interface(eoe_netif_init);
|
||||
if(found_if == NULL)
|
||||
|
@ -384,55 +351,11 @@ void main_run(void * arg)
|
|||
}
|
||||
/* Init EoE */
|
||||
EOE_config(&eoe_config);
|
||||
EOE_init();
|
||||
/* Init EtherCAT slave stack */
|
||||
ecat_slv_init(&config);
|
||||
for(;;)
|
||||
{
|
||||
if(config.use_interrupt != 0)
|
||||
{
|
||||
/* Wait for incoming event from application or EtherCAT stack */
|
||||
flags_wait_any (ecat_events, mask, &flags);
|
||||
/* Cyclic event */
|
||||
if(flags & EVENT_PERIODIC)
|
||||
{
|
||||
DIG_process(DIG_PROCESS_WD_FLAG);
|
||||
ecat_slv_poll();
|
||||
ESC_eoeprocess_tx();
|
||||
flags_clr(ecat_events, EVENT_PERIODIC);
|
||||
}
|
||||
/* Low prio interrupt from the ESC */
|
||||
if(flags & EVENT_ISR)
|
||||
{
|
||||
ecat_slv_poll();
|
||||
ESC_eoeprocess_tx();
|
||||
flags_clr(ecat_events, EVENT_ISR);
|
||||
ESC_interrupt_enable(ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
|
||||
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP);
|
||||
|
||||
}
|
||||
/* The TCP/IP stack have posted a TX job */
|
||||
if(flags & EVENT_TX)
|
||||
{
|
||||
ESC_eoeprocess_tx();
|
||||
flags_clr(ecat_events, EVENT_TX);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ecat_slv();
|
||||
ESC_eoeprocess_tx();
|
||||
}
|
||||
}
|
||||
}
|
||||
rprintf ("Hello world\n");
|
||||
ecat_slv_init (&config);
|
||||
|
||||
/* Start the main application loop */
|
||||
int main(void)
|
||||
{
|
||||
rprintf("Hello Main\n");
|
||||
task_spawn ("soes", main_run, 4, 2048, NULL);
|
||||
/* The stack is run from interrupt and a worker thread in esc_hw.c */
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
|
Binary file not shown.
|
@ -1,352 +0,0 @@
|
|||
#ifndef SOES_V1
|
||||
#include <stddef.h>
|
||||
#include "utypes.h"
|
||||
#include "esc.h"
|
||||
#include "esc_coe.h"
|
||||
#include "esc_foe.h"
|
||||
#include "esc_eoe.h"
|
||||
#include "config.h"
|
||||
#include "slave.h"
|
||||
|
||||
/* Global variables used by the stack */
|
||||
uint8_t MBX[MBXBUFFERS * MAX(MBXSIZE,MBXSIZEBOOT)];
|
||||
_MBXcontrol MBXcontrol[MBXBUFFERS];
|
||||
_ESCvar ESCvar;
|
||||
|
||||
/* Application variables */
|
||||
_Rbuffer Rb;
|
||||
_Wbuffer Wb;
|
||||
_Cbuffer Cb;
|
||||
_Mbuffer Mb;
|
||||
|
||||
/* Private variables */
|
||||
static volatile int watchdog;
|
||||
|
||||
/** Mandatory: Function to pre-qualify the incoming SDO download.
|
||||
*
|
||||
* @param[in] index = index of SDO download request to check
|
||||
* @param[in] sub-index = sub-index of SDO download request to check
|
||||
* @return 1 if the SDO Download is correct. 0 If not correct.
|
||||
*/
|
||||
int ESC_pre_objecthandler (uint16_t index, uint8_t subindex)
|
||||
{
|
||||
int result = 1;
|
||||
|
||||
if(ESCvar.pre_object_download_hook)
|
||||
{
|
||||
result = (ESCvar.pre_object_download_hook)(index, subindex);
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/** Mandatory: Hook called from the slave stack SDO Download handler to act on
|
||||
* user specified Index and Sub-index.
|
||||
*
|
||||
* @param[in] index = index of SDO download request to handle
|
||||
* @param[in] sub-index = sub-index of SDO download request to handle
|
||||
*/
|
||||
void ESC_objecthandler (uint16_t index, uint8_t subindex)
|
||||
{
|
||||
switch (index)
|
||||
{
|
||||
/* Handle post-write of parameter values */
|
||||
case 0x8000:
|
||||
{
|
||||
cb_post_write_Parameters(subindex);
|
||||
break;
|
||||
}
|
||||
case 0x8001:
|
||||
{
|
||||
cb_post_write_variableRW(subindex);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
if(ESCvar.post_object_download_hook != NULL)
|
||||
{
|
||||
(ESCvar.post_object_download_hook)(index, subindex);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/** Mandatory: Hook called from the slave stack ESC_stopoutputs to act on state changes
|
||||
* forcing us to stop outputs. Here we can set them to a safe state.
|
||||
* set
|
||||
*/
|
||||
void APP_safeoutput (void)
|
||||
{
|
||||
DPRINT ("APP_safeoutput\n");
|
||||
|
||||
if(ESCvar.safeoutput_override != NULL)
|
||||
{
|
||||
(ESCvar.safeoutput_override)();
|
||||
}
|
||||
else
|
||||
{
|
||||
// Set safe values for Wb.LEDgroup1
|
||||
Wb.LEDgroup1.LED = 0;
|
||||
// Set safe values for Wb.LEDgroup2
|
||||
Wb.LEDgroup2.LED = 0;
|
||||
// Set safe values for Wb.LEDgroup3
|
||||
Wb.LEDgroup3.LED = 0;
|
||||
// Set safe values for Wb.LEDgroup4
|
||||
Wb.LEDgroup4.LED = 0;
|
||||
// Set safe values for Wb.LEDgroup5
|
||||
Wb.LEDgroup5.LED5 = 0;
|
||||
Wb.LEDgroup5.LED678 = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/** Mandatory: Write local process data to Sync Manager 3, Master Inputs.
|
||||
*/
|
||||
void TXPDO_update (void)
|
||||
{
|
||||
if(ESCvar.txpdo_override != NULL)
|
||||
{
|
||||
(ESCvar.txpdo_override)();
|
||||
}
|
||||
else
|
||||
{
|
||||
ESC_write (SM3_sma, &Rb, ESCvar.TXPDOsize);
|
||||
}
|
||||
}
|
||||
|
||||
/** Mandatory: Read Sync Manager 2 to local process data, Master Outputs.
|
||||
*/
|
||||
void RXPDO_update (void)
|
||||
{
|
||||
if(ESCvar.rxpdo_override != NULL)
|
||||
{
|
||||
(ESCvar.rxpdo_override)();
|
||||
}
|
||||
else
|
||||
{
|
||||
ESC_read (SM2_sma, &Wb, ESCvar.RXPDOsize);
|
||||
}
|
||||
}
|
||||
|
||||
/** Mandatory: Function to update local I/O, call read ethercat outputs, call
|
||||
* write ethercat inputs. Implement watch-dog counter to count-out if we have
|
||||
* made state change affecting the App.state.
|
||||
*/
|
||||
void DIG_process (uint8_t flags)
|
||||
{
|
||||
/* Handle watchdog */
|
||||
if((flags & DIG_PROCESS_WD_FLAG) > 0)
|
||||
{
|
||||
|
||||
if (CC_ATOMIC_GET(watchdog) > 0)
|
||||
{
|
||||
CC_ATOMIC_SUB(watchdog, 1);
|
||||
}
|
||||
|
||||
if ((CC_ATOMIC_GET(watchdog) <= 0) &&
|
||||
((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0))
|
||||
{
|
||||
DPRINT("DIG_process watchdog expired\n");
|
||||
ESC_stopoutput();
|
||||
/* watchdog, invalid outputs */
|
||||
ESC_ALerror (ALERR_WATCHDOG);
|
||||
/* goto safe-op with error bit set */
|
||||
ESC_ALstatus (ESCsafeop | ESCerror);
|
||||
}
|
||||
else if(((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) == 0))
|
||||
{
|
||||
CC_ATOMIC_SET(watchdog, ESCvar.watchdogcnt);
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Outputs */
|
||||
if ((flags & DIG_PROCESS_OUTPUTS_FLAG) > 0)
|
||||
{
|
||||
if(((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0) &&
|
||||
(ESCvar.ALevent & ESCREG_ALEVENT_SM2))
|
||||
{
|
||||
RXPDO_update();
|
||||
CC_ATOMIC_SET(watchdog, ESCvar.watchdogcnt);
|
||||
if(ESCvar.dcsync > 0)
|
||||
{
|
||||
CC_ATOMIC_ADD(ESCvar.synccounter, 1);
|
||||
}
|
||||
/* Set outputs */
|
||||
cb_set_LEDgroup1();
|
||||
cb_set_LEDgroup2();
|
||||
cb_set_LEDgroup3();
|
||||
cb_set_LEDgroup4();
|
||||
cb_set_LEDgroup5();
|
||||
}
|
||||
else if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
|
||||
{
|
||||
RXPDO_update();
|
||||
}
|
||||
}
|
||||
|
||||
/* Call application */
|
||||
if ((flags & DIG_PROCESS_APP_HOOK_FLAG) > 0)
|
||||
{
|
||||
|
||||
if((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0)
|
||||
{
|
||||
CC_ATOMIC_SUB(ESCvar.synccounter, 1);
|
||||
}
|
||||
|
||||
if((ESCvar.dcsync > 0) &&
|
||||
((CC_ATOMIC_GET(ESCvar.synccounter) < -ESCvar.synccounterlimit) ||
|
||||
(CC_ATOMIC_GET(ESCvar.synccounter) > ESCvar.synccounterlimit)))
|
||||
{
|
||||
if((CC_ATOMIC_GET(ESCvar.App.state) & APPSTATE_OUTPUT) > 0)
|
||||
{
|
||||
DPRINT("sync error = %d\n", ESCvar.synccounter);
|
||||
ESC_stopoutput();
|
||||
/* Sync error */
|
||||
ESC_ALerror (ALERR_SYNCERROR);
|
||||
/* goto safe-op with error bit set */
|
||||
ESC_ALstatus (ESCsafeop | ESCerror);
|
||||
CC_ATOMIC_SET(ESCvar.synccounter, 0);
|
||||
}
|
||||
}
|
||||
/* Call application callback if set */
|
||||
if (ESCvar.application_hook != NULL)
|
||||
{
|
||||
(ESCvar.application_hook)();
|
||||
}
|
||||
}
|
||||
|
||||
/* Handle Inputs */
|
||||
if ((flags & DIG_PROCESS_INPUTS_FLAG) > 0)
|
||||
{
|
||||
if(CC_ATOMIC_GET(ESCvar.App.state) > 0)
|
||||
{
|
||||
/* Update inputs */
|
||||
cb_get_Button1();
|
||||
cb_get_Button2();
|
||||
TXPDO_update();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
|
||||
* control what interrupts that should be served and re-activated with
|
||||
* event mask argument
|
||||
*/
|
||||
void ecat_slv_worker (uint32_t event_mask)
|
||||
{
|
||||
do
|
||||
{
|
||||
/* Check the state machine */
|
||||
ESC_state();
|
||||
/* Check the SM activation event */
|
||||
ESC_sm_act_event();
|
||||
|
||||
/* Check mailboxes */
|
||||
while ((ESC_mbxprocess() > 0) || (ESCvar.txcue > 0))
|
||||
{
|
||||
ESC_coeprocess();
|
||||
ESC_foeprocess();
|
||||
ESC_xoeprocess();
|
||||
}
|
||||
|
||||
/* Call emulated eeprom handler if set */
|
||||
if (ESCvar.esc_hw_eep_handler != NULL)
|
||||
{
|
||||
(ESCvar.esc_hw_eep_handler)();
|
||||
}
|
||||
|
||||
CC_ATOMIC_SET(ESCvar.ALevent, ESC_ALeventread());
|
||||
|
||||
}while(ESCvar.ALevent & event_mask);
|
||||
|
||||
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | event_mask);
|
||||
}
|
||||
|
||||
/**
|
||||
* ISR function. It should be called from ISR for applications entirely driven by
|
||||
* interrupts.
|
||||
* Read and handle events for the EtherCAT state, status, mailbox and eeprom.
|
||||
*/
|
||||
void ecat_slv_isr (void)
|
||||
{
|
||||
ecat_slv_worker(ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
|
||||
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP);
|
||||
}
|
||||
|
||||
/**
|
||||
* Polling function. It should be called periodically for an application
|
||||
* when only SM2/DC interrupt is active.
|
||||
* Read and handle events for the EtherCAT state, status, mailbox and eeprom.
|
||||
*/
|
||||
void ecat_slv_poll (void)
|
||||
{
|
||||
/* Read local time from ESC*/
|
||||
ESC_read (ESCREG_LOCALTIME, (void *) &ESCvar.Time, sizeof (ESCvar.Time));
|
||||
ESCvar.Time = etohl (ESCvar.Time);
|
||||
|
||||
/* Check the state machine */
|
||||
ESC_state();
|
||||
/* Check the SM activation event */
|
||||
ESC_sm_act_event();
|
||||
|
||||
/* Check mailboxes */
|
||||
if (ESC_mbxprocess())
|
||||
{
|
||||
ESC_coeprocess();
|
||||
ESC_foeprocess();
|
||||
ESC_eoeprocess();
|
||||
ESC_xoeprocess();
|
||||
}
|
||||
|
||||
/* Call emulated eeprom handler if set */
|
||||
if (ESCvar.esc_hw_eep_handler != NULL)
|
||||
{
|
||||
(ESCvar.esc_hw_eep_handler)();
|
||||
}
|
||||
}
|
||||
|
||||
void ecat_slv (void)
|
||||
{
|
||||
ecat_slv_poll();
|
||||
DIG_process(DIG_PROCESS_WD_FLAG | DIG_PROCESS_OUTPUTS_FLAG |
|
||||
DIG_PROCESS_APP_HOOK_FLAG | DIG_PROCESS_INPUTS_FLAG);
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the slave stack.
|
||||
*/
|
||||
void ecat_slv_init (esc_cfg_t * config)
|
||||
{
|
||||
DPRINT ("Slave stack init started\n");
|
||||
|
||||
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
|
||||
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
|
||||
|
||||
/* Init watchdog */
|
||||
watchdog = config->watchdog_cnt;
|
||||
|
||||
/* Call stack configuration */
|
||||
ESC_config (config);
|
||||
/* Call HW init */
|
||||
ESC_init (config);
|
||||
|
||||
/* wait until ESC is started up */
|
||||
while ((ESCvar.DLstatus & 0x0001) == 0)
|
||||
{
|
||||
ESC_read (ESCREG_DLSTATUS, (void *) &ESCvar.DLstatus,
|
||||
sizeof (ESCvar.DLstatus));
|
||||
ESCvar.DLstatus = etohs (ESCvar.DLstatus);
|
||||
}
|
||||
|
||||
/* Init FoE */
|
||||
FOE_init();
|
||||
|
||||
/* reset ESC to init state */
|
||||
ESC_ALstatus (ESCinit);
|
||||
ESC_ALerror (ALERR_NONE);
|
||||
ESC_stopmbx();
|
||||
ESC_stopinput();
|
||||
ESC_stopoutput();
|
||||
}
|
||||
#endif
|
|
@ -1,99 +0,0 @@
|
|||
#ifndef __SLAVE_H__
|
||||
#define __SLAVE_H__
|
||||
|
||||
#include "utypes.h"
|
||||
#include "esc.h"
|
||||
|
||||
/**
|
||||
* This function gets input values and updates Rb.Button1
|
||||
*/
|
||||
void cb_get_Button1();
|
||||
|
||||
/**
|
||||
* This function gets input values and updates Rb.Button2
|
||||
*/
|
||||
void cb_get_Button2();
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup1
|
||||
*/
|
||||
void cb_set_LEDgroup1();
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup2
|
||||
*/
|
||||
void cb_set_LEDgroup2();
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup3
|
||||
*/
|
||||
void cb_set_LEDgroup3();
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup4
|
||||
*/
|
||||
void cb_set_LEDgroup4();
|
||||
|
||||
/**
|
||||
* This function sets output values according to Wb.LEDgroup5
|
||||
*/
|
||||
void cb_set_LEDgroup5();
|
||||
|
||||
/**
|
||||
* This function is called after a SDO write of the object Cb.Parameters.
|
||||
*/
|
||||
void cb_post_write_Parameters(int subindex);
|
||||
|
||||
/**
|
||||
* This function is called after a SDO write of the object Cb.variableRW.
|
||||
*/
|
||||
void cb_post_write_variableRW(int subindex);
|
||||
|
||||
#define DIG_PROCESS_INPUTS_FLAG 0x01
|
||||
#define DIG_PROCESS_OUTPUTS_FLAG 0x02
|
||||
#define DIG_PROCESS_WD_FLAG 0x04
|
||||
#define DIG_PROCESS_APP_HOOK_FLAG 0x08
|
||||
/** Implements the watch-dog counter to count if we should make a state change
|
||||
* due to missing incoming SM2 events. Updates local I/O and run the application
|
||||
* in the following order, call read EtherCAT outputs, execute user provided
|
||||
* application hook and call write EtherCAT inputs.
|
||||
*
|
||||
* @param[in] flags = User input what to execute
|
||||
*/
|
||||
void DIG_process (uint8_t flags);
|
||||
|
||||
/**
|
||||
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
|
||||
* control what interrupts that should be served and re-activated with
|
||||
* event mask argument
|
||||
*
|
||||
* @param[in] event_mask = Event mask for interrupts to serve and re-activate
|
||||
* after served
|
||||
*/
|
||||
void ecat_slv_worker (uint32_t event_mask);
|
||||
|
||||
/**
|
||||
* ISR for SM0/1, EEPROM and AL CONTROL events in a SM/DC
|
||||
* synchronization application
|
||||
*/
|
||||
CC_DEPRECATED void ecat_slv_isr (void);
|
||||
|
||||
/**
|
||||
* Poll SM0/1, EEPROM and AL CONTROL events in a SM/DC synchronization
|
||||
* application
|
||||
*/
|
||||
void ecat_slv_poll (void);
|
||||
|
||||
/**
|
||||
* Poll all events in a free-run application
|
||||
*/
|
||||
void ecat_slv (void);
|
||||
|
||||
/**
|
||||
* Initialize the slave stack
|
||||
*
|
||||
* @param[in] config = User input how to configure the stack
|
||||
*/
|
||||
void ecat_slv_init (esc_cfg_t * config);
|
||||
|
||||
#endif /* __SLAVE_H__ */
|
File diff suppressed because it is too large
Load Diff
Binary file not shown.
|
@ -0,0 +1,14 @@
|
|||
#include <stddef.h>
|
||||
#include "utypes.h"
|
||||
#include "ecat_options.h"
|
||||
#include "esc.h"
|
||||
|
||||
/* Global variables used by the stack */
|
||||
uint8_t MBX[MBXBUFFERS * MAX(MBXSIZE,MBXSIZEBOOT)];
|
||||
_MBXcontrol MBXcontrol[MBXBUFFERS];
|
||||
_ESCvar ESCvar;
|
||||
_SMmap SMmap2[MAX_MAPPINGS_SM2];
|
||||
_SMmap SMmap3[MAX_MAPPINGS_SM3];
|
||||
|
||||
/* Application variables */
|
||||
_Objects _Obj;
|
|
@ -0,0 +1,421 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<Slave xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="com.rtlabs.emf.esx" fileVersion="2" id="slave30" productCode="0x3030">
|
||||
<Name>slave30 product</Name>
|
||||
<Vendor>
|
||||
<Id>0x1337</Id>
|
||||
<Name>rt-labs</Name>
|
||||
</Vendor>
|
||||
<Group>
|
||||
<Type>sdk test</Type>
|
||||
<Name>sdk test</Name>
|
||||
</Group>
|
||||
<Fmmu>Outputs</Fmmu>
|
||||
<Fmmu>Inputs</Fmmu>
|
||||
<Fmmu>MBoxState</Fmmu>
|
||||
<Sm ControlByte="0x26" DefaultSize="128" StartAddress="0x1000">MBoxOut</Sm>
|
||||
<Sm ControlByte="0x22" DefaultSize="128" StartAddress="0x1080">MBoxIn</Sm>
|
||||
<Sm ControlByte="0x64" DefaultSize="0" StartAddress="0x1100">Outputs</Sm>
|
||||
<Sm ControlByte="0x20" DefaultSize="0" StartAddress="0x1180">Inputs</Sm>
|
||||
<Mailbox CoE="true" EoE="true">
|
||||
<Bootstrap Length="128" Start="0x1000"/>
|
||||
<Standard Length="128" Start="0x1000"/>
|
||||
</Mailbox>
|
||||
<Eeprom>
|
||||
<ConfigData>8006810600000000</ConfigData>
|
||||
<BootStrap>0010800080108000</BootStrap>
|
||||
</Eeprom>
|
||||
<Dictionary>
|
||||
<Item>
|
||||
<Index>0x1009</Index>
|
||||
<Name>Hardware Version</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>1.0</DefaultValue>
|
||||
<Length>4</Length>
|
||||
</Item>
|
||||
<Item>
|
||||
<Index>0x100A</Index>
|
||||
<Name>Software Version</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>1.0</DefaultValue>
|
||||
<Length>4</Length>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1000</Index>
|
||||
<Name>Device Type</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x00001389</DefaultValue>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1008</Index>
|
||||
<Name>Device Name</Name>
|
||||
<DataType>VISIBLE_STRING</DataType>
|
||||
<DefaultValue>slave30</DefaultValue>
|
||||
<Length>7</Length>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1018</Index>
|
||||
<Name>Identity Object</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Vendor ID</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x1337</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>Product Code</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x3030</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Name>Revision Number</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Name>Serial Number</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x00000000</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1600</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>LED0</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70000108</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1601</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>LED1</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x70010108</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Button1</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0x60000108</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C00</Index>
|
||||
<Name>Sync Manager Communication Type</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>Communications Type SM0</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>Communications Type SM1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x03</Index>
|
||||
<Name>Communications Type SM2</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>3</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x04</Index>
|
||||
<Name>Communications Type SM3</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C12</Index>
|
||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>PDO Mapping</Name>
|
||||
<DataType>UNSIGNED16</DataType>
|
||||
<DefaultValue>0x1600</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x02</Index>
|
||||
<Name>PDO Mapping</Name>
|
||||
<DataType>UNSIGNED16</DataType>
|
||||
<DefaultValue>0x1601</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x1C13</Index>
|
||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||
<DataType>ARRAY</DataType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Name>PDO Mapping</Name>
|
||||
<DataType>UNSIGNED16</DataType>
|
||||
<DefaultValue>0x1A00</DefaultValue>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x6000</Index>
|
||||
<Name>Buttons</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>Buttons</Variable>
|
||||
<VariableType>Input</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>Button1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
<Variable>Button1</Variable>
|
||||
<VariableType>Input</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x7000</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>LEDgroup0</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED0</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>LED0</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x7001</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>LEDgroup1</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>LED1</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<Variable>LED1</Variable>
|
||||
<VariableType>Output</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x8000</Index>
|
||||
<Name>Parameters</Name>
|
||||
<DataType>RECORD</DataType>
|
||||
<Variable>Parameters</Variable>
|
||||
<VariableType>Parameter</VariableType>
|
||||
<SubItem>
|
||||
<Index>0x00</Index>
|
||||
<Name>Max SubIndex</Name>
|
||||
<DataType>UNSIGNED8</DataType>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Index>0x01</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>Multiplier</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<PdoMapping>TX_AND_RX</PdoMapping>
|
||||
<Variable>Multiplier</Variable>
|
||||
<VariableType>Parameter</VariableType>
|
||||
</SubItem>
|
||||
</Item>
|
||||
<Item Managed="true">
|
||||
<Index>0x8001</Index>
|
||||
<Access>RO</Access>
|
||||
<Name>variableRW</Name>
|
||||
<DataType>UNSIGNED32</DataType>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
<Variable>variableRW</Variable>
|
||||
<VariableType>Parameter</VariableType>
|
||||
</Item>
|
||||
</Dictionary>
|
||||
<SmAssignment>
|
||||
<Index>0x1C12</Index>
|
||||
<Entry>
|
||||
<Index>0x01</Index>
|
||||
<AssignedPdo>0x1600</AssignedPdo>
|
||||
</Entry>
|
||||
<Entry>
|
||||
<Index>0x02</Index>
|
||||
<AssignedPdo>0x1601</AssignedPdo>
|
||||
</Entry>
|
||||
</SmAssignment>
|
||||
<SmAssignment>
|
||||
<Index>0x1C13</Index>
|
||||
<Entry>
|
||||
<Index>0x01</Index>
|
||||
<AssignedPdo>0x1A00</AssignedPdo>
|
||||
</Entry>
|
||||
</SmAssignment>
|
||||
<RxPdo>
|
||||
<Index>0x1600</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<Entry>
|
||||
<Index>0x1</Index>
|
||||
<MappedIndex>0x7000</MappedIndex>
|
||||
<MappedSubIndex>0x01</MappedSubIndex>
|
||||
<Variable>LED0</Variable>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<RxPdo>
|
||||
<Index>0x1601</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<Entry>
|
||||
<Index>0x1</Index>
|
||||
<MappedIndex>0x7001</MappedIndex>
|
||||
<MappedSubIndex>0x01</MappedSubIndex>
|
||||
<Variable>LED1</Variable>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<TxPdo>
|
||||
<Index>0x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<Entry>
|
||||
<Index>0x1</Index>
|
||||
<MappedIndex>0x6000</MappedIndex>
|
||||
<MappedSubIndex>0x01</MappedSubIndex>
|
||||
<Variable>Button1</Variable>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<Input>
|
||||
<Index>0x6000</Index>
|
||||
<Name>Buttons</Name>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Name>Button1</Name>
|
||||
<Type>UNSIGNED8</Type>
|
||||
<PdoMapping>TX</PdoMapping>
|
||||
</Member>
|
||||
</Input>
|
||||
<Output>
|
||||
<Index>0x7000</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Name>LED0</Name>
|
||||
<Type>UNSIGNED8</Type>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
</Output>
|
||||
<Output>
|
||||
<Index>0x7001</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Name>LED1</Name>
|
||||
<Type>UNSIGNED8</Type>
|
||||
<PdoMapping>RX</PdoMapping>
|
||||
</Member>
|
||||
</Output>
|
||||
<Parameter>
|
||||
<Index>0x8000</Index>
|
||||
<Name>Parameters</Name>
|
||||
<PdoMapping>NONE</PdoMapping>
|
||||
<ObjectType>RECORD</ObjectType>
|
||||
<Member>
|
||||
<Index>0x01</Index>
|
||||
<Name>Multiplier</Name>
|
||||
<Type>UNSIGNED32</Type>
|
||||
<PdoMapping>TX_AND_RX</PdoMapping>
|
||||
</Member>
|
||||
</Parameter>
|
||||
<Parameter>
|
||||
<Index>0x8001</Index>
|
||||
<Name>variableRW</Name>
|
||||
<Type>UNSIGNED32</Type>
|
||||
<PdoMapping>NONE</PdoMapping>
|
||||
<ObjectType>VAR</ObjectType>
|
||||
</Parameter>
|
||||
</Slave>
|
|
@ -0,0 +1,780 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<EtherCATInfo>
|
||||
<Vendor>
|
||||
<Id>#x1337</Id>
|
||||
<Name LcId="1033">rt-labs</Name>
|
||||
</Vendor>
|
||||
<Descriptions>
|
||||
<Groups>
|
||||
<Group>
|
||||
<Type>sdk test</Type>
|
||||
<Name LcId="1033">sdk test</Name>
|
||||
</Group>
|
||||
</Groups>
|
||||
<Devices>
|
||||
<Device Physics="YY">
|
||||
<Type ProductCode="#x3030" RevisionNo="0">slave30</Type>
|
||||
<Name LcId="1033">slave30 product</Name>
|
||||
<GroupType>sdk test</GroupType>
|
||||
<Profile>
|
||||
<ProfileNo>5001</ProfileNo>
|
||||
<AddInfo>0</AddInfo>
|
||||
<Dictionary>
|
||||
<DataTypes>
|
||||
<DataType>
|
||||
<Name>DT1018</Name>
|
||||
<BitSize>144</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>Vendor ID</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>2</SubIdx>
|
||||
<Name>Product Code</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>48</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>3</SubIdx>
|
||||
<Name>Revision Number</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>80</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>4</SubIdx>
|
||||
<Name>Serial Number</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>112</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1600</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>LED0</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1601</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>LED1</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1A00</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>Button1</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C00ARR</Name>
|
||||
<BaseType>USINT</BaseType>
|
||||
<BitSize>32</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>4</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C00</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C00ARR</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C12ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>32</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>2</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C12</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C12ARR</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C13ARR</Name>
|
||||
<BaseType>UINT</BaseType>
|
||||
<BitSize>16</BitSize>
|
||||
<ArrayInfo>
|
||||
<LBound>1</LBound>
|
||||
<Elements>1</Elements>
|
||||
</ArrayInfo>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT1C13</Name>
|
||||
<BitSize>32</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Elements</Name>
|
||||
<Type>DT1C13ARR</Type>
|
||||
<BitSize>16</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT6000</Name>
|
||||
<BitSize>24</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>Button1</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<PdoMapping>T</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT7000</Name>
|
||||
<BitSize>24</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>LED0</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<PdoMapping>R</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT7001</Name>
|
||||
<BitSize>24</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>LED1</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<PdoMapping>R</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>DT8000</Name>
|
||||
<BitSize>48</BitSize>
|
||||
<SubItem>
|
||||
<SubIdx>0</SubIdx>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Type>USINT</Type>
|
||||
<BitSize>8</BitSize>
|
||||
<BitOffs>0</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<SubIdx>1</SubIdx>
|
||||
<Name>Multiplier</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<BitOffs>16</BitOffs>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<PdoMapping>TR</PdoMapping>
|
||||
</Flags>
|
||||
</SubItem>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>STRING(4)</Name>
|
||||
<BitSize>32</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>UDINT</Name>
|
||||
<BitSize>32</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>UINT</Name>
|
||||
<BitSize>16</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>STRING(7)</Name>
|
||||
<BitSize>56</BitSize>
|
||||
</DataType>
|
||||
<DataType>
|
||||
<Name>USINT</Name>
|
||||
<BitSize>8</BitSize>
|
||||
</DataType>
|
||||
</DataTypes>
|
||||
<Objects>
|
||||
<Object>
|
||||
<Index>#x1009</Index>
|
||||
<Name>Hardware Version</Name>
|
||||
<Type>STRING(4)</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Info>
|
||||
<DefaultString>1.0</DefaultString>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<Category>o</Category>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x100A</Index>
|
||||
<Name>Software Version</Name>
|
||||
<Type>STRING(4)</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Info>
|
||||
<DefaultString>1.0</DefaultString>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1000</Index>
|
||||
<Name>Device Type</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Info>
|
||||
<DefaultValue>#x00001389</DefaultValue>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
<Category>m</Category>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1008</Index>
|
||||
<Name>Device Name</Name>
|
||||
<Type>STRING(7)</Type>
|
||||
<BitSize>56</BitSize>
|
||||
<Info>
|
||||
<DefaultString>slave30</DefaultString>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1018</Index>
|
||||
<Name>Identity Object</Name>
|
||||
<Type>DT1018</Type>
|
||||
<BitSize>144</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Vendor ID</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1337</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Product Code</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x3030</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Revision Number</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Serial Number</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x00000000</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1600</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<Type>DT1600</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>LED0</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x70000108</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1601</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<Type>DT1601</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>LED1</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x70010108</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<Type>DT1A00</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Button1</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x60000108</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1C00</Index>
|
||||
<Name>Sync Manager Communication Type</Name>
|
||||
<Type>DT1C00</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Communications Type SM0</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Communications Type SM1</Name>
|
||||
<Info>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Communications Type SM2</Name>
|
||||
<Info>
|
||||
<DefaultValue>3</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Communications Type SM3</Name>
|
||||
<Info>
|
||||
<DefaultValue>4</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1C12</Index>
|
||||
<Name>Sync Manager 2 PDO Assignment</Name>
|
||||
<Type>DT1C12</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>2</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1600</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1601</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x1C13</Index>
|
||||
<Name>Sync Manager 3 PDO Assignment</Name>
|
||||
<Type>DT1C13</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>PDO Mapping</Name>
|
||||
<Info>
|
||||
<DefaultValue>#x1A00</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x6000</Index>
|
||||
<Name>Buttons</Name>
|
||||
<Type>DT6000</Type>
|
||||
<BitSize>24</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Button1</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x7000</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<Type>DT7000</Type>
|
||||
<BitSize>24</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>LED0</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x7001</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<Type>DT7001</Type>
|
||||
<BitSize>24</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>LED1</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x8000</Index>
|
||||
<Name>Parameters</Name>
|
||||
<Type>DT8000</Type>
|
||||
<BitSize>48</BitSize>
|
||||
<Info>
|
||||
<SubItem>
|
||||
<Name>Max SubIndex</Name>
|
||||
<Info>
|
||||
<DefaultValue>1</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
<SubItem>
|
||||
<Name>Multiplier</Name>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
</SubItem>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
<Object>
|
||||
<Index>#x8001</Index>
|
||||
<Name>variableRW</Name>
|
||||
<Type>UDINT</Type>
|
||||
<BitSize>32</BitSize>
|
||||
<Info>
|
||||
<DefaultValue>0</DefaultValue>
|
||||
</Info>
|
||||
<Flags>
|
||||
<Access>ro</Access>
|
||||
</Flags>
|
||||
</Object>
|
||||
</Objects>
|
||||
</Dictionary>
|
||||
</Profile>
|
||||
<Fmmu>Outputs</Fmmu>
|
||||
<Fmmu>Inputs</Fmmu>
|
||||
<Fmmu>MBoxState</Fmmu>
|
||||
<Sm ControlByte="#x26" DefaultSize="128" Enable="1" StartAddress="#x1000">MBoxOut</Sm>
|
||||
<Sm ControlByte="#x22" DefaultSize="128" Enable="1" StartAddress="#x1080">MBoxIn</Sm>
|
||||
<Sm ControlByte="#x64" Enable="1" StartAddress="#x1100">Outputs</Sm>
|
||||
<Sm ControlByte="#x20" Enable="1" StartAddress="#x1180">Inputs</Sm>
|
||||
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||
<Index>#x1600</Index>
|
||||
<Name>LEDgroup0</Name>
|
||||
<Entry>
|
||||
<Index>#x7000</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>8</BitLen>
|
||||
<Name>LED0</Name>
|
||||
<DataType>USINT</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<RxPdo Fixed="true" Mandatory="true" Sm="2">
|
||||
<Index>#x1601</Index>
|
||||
<Name>LEDgroup1</Name>
|
||||
<Entry>
|
||||
<Index>#x7001</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>8</BitLen>
|
||||
<Name>LED1</Name>
|
||||
<DataType>USINT</DataType>
|
||||
</Entry>
|
||||
</RxPdo>
|
||||
<TxPdo Fixed="true" Mandatory="true" Sm="3">
|
||||
<Index>#x1A00</Index>
|
||||
<Name>Buttons</Name>
|
||||
<Entry>
|
||||
<Index>#x6000</Index>
|
||||
<SubIndex>#x1</SubIndex>
|
||||
<BitLen>8</BitLen>
|
||||
<Name>Button1</Name>
|
||||
<DataType>USINT</DataType>
|
||||
</Entry>
|
||||
</TxPdo>
|
||||
<Mailbox DataLinkLayer="true">
|
||||
<EoE/>
|
||||
<CoE CompleteAccess="false" PdoAssign="false" PdoUpload="false" SdoInfo="true"/>
|
||||
</Mailbox>
|
||||
<Eeprom>
|
||||
<ByteSize>256</ByteSize>
|
||||
<ConfigData>8006810600000000</ConfigData>
|
||||
<BootStrap>0010800080108000</BootStrap>
|
||||
</Eeprom>
|
||||
</Device>
|
||||
</Devices>
|
||||
</Descriptions>
|
||||
</EtherCATInfo>
|
|
@ -0,0 +1,161 @@
|
|||
#include "esc_coe.h"
|
||||
#include "utypes.h"
|
||||
#include <stddef.h>
|
||||
|
||||
#ifndef HW_REV
|
||||
#define HW_REV "1.0"
|
||||
#endif
|
||||
|
||||
#ifndef SW_REV
|
||||
#define SW_REV "1.0"
|
||||
#endif
|
||||
|
||||
static const char acName1009[] = "Hardware Version";
|
||||
static const char acName100A[] = "Software Version";
|
||||
static const char acName1000[] = "Device Type";
|
||||
static const char acName1008[] = "Device Name";
|
||||
static const char acName1018[] = "Identity Object";
|
||||
static const char acName1018_00[] = "Max SubIndex";
|
||||
static const char acName1018_01[] = "Vendor ID";
|
||||
static const char acName1018_02[] = "Product Code";
|
||||
static const char acName1018_03[] = "Revision Number";
|
||||
static const char acName1018_04[] = "Serial Number";
|
||||
static const char acName1600[] = "LEDgroup0";
|
||||
static const char acName1600_00[] = "Max SubIndex";
|
||||
static const char acName1600_01[] = "LED0";
|
||||
static const char acName1601[] = "LEDgroup1";
|
||||
static const char acName1601_00[] = "Max SubIndex";
|
||||
static const char acName1601_01[] = "LED1";
|
||||
static const char acName1A00[] = "Buttons";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "Button1";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
static const char acName1C00_00[] = "Max SubIndex";
|
||||
static const char acName1C00_01[] = "Communications Type SM0";
|
||||
static const char acName1C00_02[] = "Communications Type SM1";
|
||||
static const char acName1C00_03[] = "Communications Type SM2";
|
||||
static const char acName1C00_04[] = "Communications Type SM3";
|
||||
static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
|
||||
static const char acName1C12_00[] = "Max SubIndex";
|
||||
static const char acName1C12_01[] = "PDO Mapping";
|
||||
static const char acName1C12_02[] = "PDO Mapping";
|
||||
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||
static const char acName1C13_00[] = "Max SubIndex";
|
||||
static const char acName1C13_01[] = "PDO Mapping";
|
||||
static const char acName6000[] = "Buttons";
|
||||
static const char acName6000_00[] = "Max SubIndex";
|
||||
static const char acName6000_01[] = "Button1";
|
||||
static const char acName7000[] = "LEDgroup0";
|
||||
static const char acName7000_00[] = "Max SubIndex";
|
||||
static const char acName7000_01[] = "LED0";
|
||||
static const char acName7001[] = "LEDgroup1";
|
||||
static const char acName7001_00[] = "Max SubIndex";
|
||||
static const char acName7001_01[] = "LED1";
|
||||
static const char acName8000[] = "Parameters";
|
||||
static const char acName8000_00[] = "Max SubIndex";
|
||||
static const char acName8000_01[] = "Multiplier";
|
||||
static const char acName8001[] = "variableRW";
|
||||
|
||||
const _objd SDO1009[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 32, ATYPE_RO, acName1009, 0, HW_REV},
|
||||
};
|
||||
const _objd SDO100A[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 32, ATYPE_RO, acName100A, 0, SW_REV},
|
||||
};
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000, 0x00001389, NULL},
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 56, ATYPE_RO, acName1008, 0, "slave30"},
|
||||
};
|
||||
const _objd SDO1018[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 0x1337, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 0x3030, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 0, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 0x00000000, NULL},
|
||||
};
|
||||
const _objd SDO1600[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70000108, NULL},
|
||||
};
|
||||
const _objd SDO1601[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70010108, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60000108, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_01, 1, NULL},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_02, 2, NULL},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_03, 3, NULL},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_04, 4, NULL},
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 2, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
||||
};
|
||||
const _objd SDO6000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6000_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_TXPDO, acName6000_01, 0, &Obj.Buttons.Button1},
|
||||
};
|
||||
const _objd SDO7000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7000_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7000_01, 0, &Obj.LEDgroup0.LED0},
|
||||
};
|
||||
const _objd SDO7001[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7001_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO | ATYPE_RXPDO, acName7001_01, 0, &Obj.LEDgroup1.LED1},
|
||||
};
|
||||
const _objd SDO8000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName8000_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO | ATYPE_TXPDO | ATYPE_RXPDO, acName8000_01, 0, &Obj.Parameters.Multiplier},
|
||||
};
|
||||
const _objd SDO8001[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName8001, 0, &Obj.variableRW},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
{
|
||||
{0x1000, OTYPE_VAR, 0, 0, acName1000, SDO1000},
|
||||
{0x1008, OTYPE_VAR, 0, 0, acName1008, SDO1008},
|
||||
{0x1009, OTYPE_VAR, 0, 0, acName1009, SDO1009},
|
||||
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
|
||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 2, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 1, 0, acName1C13, SDO1C13},
|
||||
{0x6000, OTYPE_RECORD, 1, 0, acName6000, SDO6000},
|
||||
{0x7000, OTYPE_RECORD, 1, 0, acName7000, SDO7000},
|
||||
{0x7001, OTYPE_RECORD, 1, 0, acName7001, SDO7001},
|
||||
{0x8000, OTYPE_RECORD, 1, 0, acName8000, SDO8000},
|
||||
{0x8001, OTYPE_VAR, 0, 0, acName8001, SDO8001},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
|
@ -1,310 +0,0 @@
|
|||
#ifndef SOES_V1
|
||||
#include "esc_coe.h"
|
||||
#include "utypes.h"
|
||||
#include <stddef.h>
|
||||
|
||||
#ifndef HW_REV
|
||||
#define HW_REV "1.0"
|
||||
#endif
|
||||
|
||||
#ifndef SW_REV
|
||||
#define SW_REV "1.0"
|
||||
#endif
|
||||
|
||||
static const char acName1000[] = "Device Type";
|
||||
static const char acName1000_0[] = "Device Type";
|
||||
static const char acName1008[] = "Device Name";
|
||||
static const char acName1008_0[] = "Device Name";
|
||||
static const char acName1009[] = "Hardware Version";
|
||||
static const char acName1009_0[] = "Hardware Version";
|
||||
static const char acName100A[] = "Software Version";
|
||||
static const char acName100A_0[] = "Software Version";
|
||||
static const char acName1018[] = "Identity Object";
|
||||
static const char acName1018_00[] = "Max SubIndex";
|
||||
static const char acName1018_01[] = "Vendor ID";
|
||||
static const char acName1018_02[] = "Product Code";
|
||||
static const char acName1018_03[] = "Revision Number";
|
||||
static const char acName1018_04[] = "Serial Number";
|
||||
static const char acName10F1[] = "ErrorSettings";
|
||||
static const char acName10F1_00[] = "Max SubIndex";
|
||||
static const char acName10F1_01[] = "Dummy_x01";
|
||||
static const char acName10F1_02[] = "SyncErrorCounterLimit";
|
||||
static const char acName1600[] = "LEDgroup1";
|
||||
static const char acName1600_00[] = "Max SubIndex";
|
||||
static const char acName1600_01[] = "LED";
|
||||
static const char acName1601[] = "LEDgroup2";
|
||||
static const char acName1601_00[] = "Max SubIndex";
|
||||
static const char acName1601_01[] = "LED";
|
||||
static const char acName1602[] = "LEDgroup3";
|
||||
static const char acName1602_00[] = "Max SubIndex";
|
||||
static const char acName1602_01[] = "LED";
|
||||
static const char acName1603[] = "LEDgroup4";
|
||||
static const char acName1603_00[] = "Max SubIndex";
|
||||
static const char acName1603_01[] = "LED";
|
||||
static const char acName1604[] = "LEDgroup5";
|
||||
static const char acName1604_00[] = "Max SubIndex";
|
||||
static const char acName1604_01[] = "LED5";
|
||||
static const char acName1604_02[] = "LED678";
|
||||
static const char acName1A00[] = "Button1";
|
||||
static const char acName1A00_00[] = "Max SubIndex";
|
||||
static const char acName1A00_01[] = "B";
|
||||
static const char acName1A01[] = "Button2";
|
||||
static const char acName1A01_00[] = "Max SubIndex";
|
||||
static const char acName1A01_01[] = "B";
|
||||
static const char acName1C00[] = "Sync Manager Communication Type";
|
||||
static const char acName1C00_00[] = "Max SubIndex";
|
||||
static const char acName1C00_01[] = "Communications Type SM0";
|
||||
static const char acName1C00_02[] = "Communications Type SM1";
|
||||
static const char acName1C00_03[] = "Communications Type SM2";
|
||||
static const char acName1C00_04[] = "Communications Type SM3";
|
||||
static const char acName1C12[] = "Sync Manager 2 PDO Assignment";
|
||||
static const char acName1C12_00[] = "Max SubIndex";
|
||||
static const char acName1C12_01[] = "PDO Mapping";
|
||||
static const char acName1C12_02[] = "PDO Mapping";
|
||||
static const char acName1C12_03[] = "PDO Mapping";
|
||||
static const char acName1C12_04[] = "PDO Mapping";
|
||||
static const char acName1C12_05[] = "PDO Mapping";
|
||||
static const char acName1C13[] = "Sync Manager 3 PDO Assignment";
|
||||
static const char acName1C13_00[] = "Max SubIndex";
|
||||
static const char acName1C13_01[] = "PDO Mapping";
|
||||
static const char acName1C13_02[] = "PDO Mapping";
|
||||
static const char acName1C32[] = "SyncMgrParam";
|
||||
static const char acName1C32_00[] = "Max SubIndex";
|
||||
static const char acName1C32_01[] = "SyncType";
|
||||
static const char acName1C32_02[] = "CycleTime";
|
||||
static const char acName1C32_03[] = "ShiftTime";
|
||||
static const char acName1C32_04[] = "SyncTypeSupport";
|
||||
static const char acName1C32_05[] = "MinCycleTime";
|
||||
static const char acName1C32_06[] = "CalcCopyTime";
|
||||
static const char acName1C32_07[] = "MinDelayTime";
|
||||
static const char acName1C32_08[] = "GetCycleTime";
|
||||
static const char acName1C32_09[] = "DelayTime";
|
||||
static const char acName1C32_0A[] = "Sync0CycleTime";
|
||||
static const char acName1C32_0B[] = "SMEventMissedCnt";
|
||||
static const char acName1C32_0C[] = "CycleTimeTooSmallCnt";
|
||||
static const char acName1C32_0D[] = "ShiftTimeTooSmallCnt";
|
||||
static const char acName1C32_0E[] = "RxPDOToggleFailed";
|
||||
static const char acName1C32_0F[] = "MinCycleDist";
|
||||
static const char acName1C32_10[] = "MaxCycleDist";
|
||||
static const char acName1C32_11[] = "MinSMSYNCDist";
|
||||
static const char acName1C32_12[] = "MaxSMSYNCDist";
|
||||
static const char acName1C32_14[] = "Dummy_x14";
|
||||
static const char acName1C32_20[] = "SyncError";
|
||||
static const char acName6005[] = "Button1";
|
||||
static const char acName6005_00[] = "Max SubIndex";
|
||||
static const char acName6005_01[] = "B";
|
||||
static const char acName6006[] = "Button2";
|
||||
static const char acName6006_00[] = "Max SubIndex";
|
||||
static const char acName6006_01[] = "B";
|
||||
static const char acName7005[] = "LEDgroup1";
|
||||
static const char acName7005_00[] = "Max SubIndex";
|
||||
static const char acName7005_01[] = "LED";
|
||||
static const char acName7006[] = "LEDgroup2";
|
||||
static const char acName7006_00[] = "Max SubIndex";
|
||||
static const char acName7006_01[] = "LED";
|
||||
static const char acName7007[] = "LEDgroup3";
|
||||
static const char acName7007_00[] = "Max SubIndex";
|
||||
static const char acName7007_01[] = "LED";
|
||||
static const char acName7008[] = "LEDgroup4";
|
||||
static const char acName7008_00[] = "Max SubIndex";
|
||||
static const char acName7008_01[] = "LED";
|
||||
static const char acName7009[] = "LEDgroup5";
|
||||
static const char acName7009_00[] = "Max SubIndex";
|
||||
static const char acName7009_01[] = "LED5";
|
||||
static const char acName7009_02[] = "LED678";
|
||||
static const char acName8000[] = "Parameters";
|
||||
static const char acName8000_00[] = "Max SubIndex";
|
||||
static const char acName8000_01[] = "Multiplier";
|
||||
static const char acName8001[] = "variableRW";
|
||||
static const char acName8001_0[] = "variableRW";
|
||||
|
||||
const _objd SDO1000[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1000_0, 0x00001389, NULL},
|
||||
};
|
||||
const _objd SDO1008[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 88, ATYPE_RO, acName1008_0, 0, "xmc48_slave"},
|
||||
};
|
||||
const _objd SDO1009[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 24, ATYPE_RO, acName1009_0, 0, HW_REV},
|
||||
};
|
||||
const _objd SDO100A[] =
|
||||
{
|
||||
{0x0, DTYPE_VISIBLE_STRING, 24, ATYPE_RO, acName100A_0, 0, SW_REV},
|
||||
};
|
||||
const _objd SDO1018[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1018_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_01, 0x1337, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_02, 0x4800, NULL},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_03, 0, NULL},
|
||||
{0x04, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1018_04, 0x00000000, NULL},
|
||||
};
|
||||
const _objd SDO10F1[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName10F1_00, 2, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName10F1_01, 0, &Mb.ErrorSettings.Dummy_x01},
|
||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RW, acName10F1_02, 2, &Mb.ErrorSettings.SyncErrorCounterLimit},
|
||||
};
|
||||
const _objd SDO1600[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1600_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1600_01, 0x70050120, NULL},
|
||||
};
|
||||
const _objd SDO1601[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1601_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1601_01, 0x70060108, NULL},
|
||||
};
|
||||
const _objd SDO1602[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1602_01, 0x70070108, NULL},
|
||||
};
|
||||
const _objd SDO1603[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1603_01, 0x70080108, NULL},
|
||||
};
|
||||
const _objd SDO1604[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1604_00, 2, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1604_01, 0x70090108, NULL},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1604_02, 0x70090208, NULL},
|
||||
};
|
||||
const _objd SDO1A00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60050108, NULL},
|
||||
};
|
||||
const _objd SDO1A01[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A01_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A01_01, 0x60060120, NULL},
|
||||
};
|
||||
const _objd SDO1C00[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_00, 4, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_01, 1, NULL},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_02, 2, NULL},
|
||||
{0x03, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_03, 3, NULL},
|
||||
{0x04, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C00_04, 4, NULL},
|
||||
};
|
||||
const _objd SDO1C12[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C12_00, 5, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_01, 0x1600, NULL},
|
||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_02, 0x1601, NULL},
|
||||
{0x03, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_03, 0x1602, NULL},
|
||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_04, 0x1603, NULL},
|
||||
{0x05, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C12_05, 0x1604, NULL},
|
||||
};
|
||||
const _objd SDO1C13[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C13_00, 2, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_01, 0x1A00, NULL},
|
||||
{0x02, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C13_02, 0x1A01, NULL},
|
||||
};
|
||||
const _objd SDO1C32[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C32_00, 32, NULL},
|
||||
{0x01, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_01, 1, &Mb.SyncMgrParam.SyncType},
|
||||
{0x02, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_02, 0, &Mb.SyncMgrParam.CycleTime},
|
||||
{0x03, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_03, 0, &Mb.SyncMgrParam.ShiftTime},
|
||||
{0x04, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_04, 0x6, &Mb.SyncMgrParam.SyncTypeSupport},
|
||||
{0x05, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_05, 125000, &Mb.SyncMgrParam.MinCycleTime},
|
||||
{0x06, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_06, 0, &Mb.SyncMgrParam.CalcCopyTime},
|
||||
{0x07, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_07, 0, &Mb.SyncMgrParam.MinDelayTime},
|
||||
{0x08, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_08, 0, &Mb.SyncMgrParam.GetCycleTime},
|
||||
{0x09, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_09, 0, &Mb.SyncMgrParam.DelayTime},
|
||||
{0x0A, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_0A, 0, &Mb.SyncMgrParam.Sync0CycleTime},
|
||||
{0x0B, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_0B, 0, &Mb.SyncMgrParam.SMEventMissedCnt},
|
||||
{0x0C, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_0C, 0, &Mb.SyncMgrParam.CycleTimeTooSmallCnt},
|
||||
{0x0D, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_0D, 0, &Mb.SyncMgrParam.ShiftTimeTooSmallCnt},
|
||||
{0x0E, DTYPE_UNSIGNED16, 16, ATYPE_RO, acName1C32_0E, 0, &Mb.SyncMgrParam.RxPDOToggleFailed},
|
||||
{0x0F, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_0F, 0, &Mb.SyncMgrParam.MinCycleDist},
|
||||
{0x10, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_10, 0, &Mb.SyncMgrParam.MaxCycleDist},
|
||||
{0x11, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_11, 0, &Mb.SyncMgrParam.MinSMSYNCDist},
|
||||
{0x12, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1C32_12, 0, &Mb.SyncMgrParam.MaxSMSYNCDist},
|
||||
{0x14, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C32_14, 0, &Mb.SyncMgrParam.Dummy_x14},
|
||||
{0x20, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1C32_20, 0, &Mb.SyncMgrParam.SyncError},
|
||||
};
|
||||
const _objd SDO6005[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6005_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6005_01, 0, &Rb.Button1.B},
|
||||
};
|
||||
const _objd SDO6006[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName6006_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName6006_01, 0, &Rb.Button2.B},
|
||||
};
|
||||
const _objd SDO7005[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7005_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName7005_01, 0, &Wb.LEDgroup1.LED},
|
||||
};
|
||||
const _objd SDO7006[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7006_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7006_01, 0, &Wb.LEDgroup2.LED},
|
||||
};
|
||||
const _objd SDO7007[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7007_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7007_01, 0, &Wb.LEDgroup3.LED},
|
||||
};
|
||||
const _objd SDO7008[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7008_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7008_01, 0, &Wb.LEDgroup4.LED},
|
||||
};
|
||||
const _objd SDO7009[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7009_00, 2, NULL},
|
||||
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7009_01, 0, &Wb.LEDgroup5.LED5},
|
||||
{0x02, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7009_02, 0, &Wb.LEDgroup5.LED678},
|
||||
};
|
||||
const _objd SDO8000[] =
|
||||
{
|
||||
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName8000_00, 1, NULL},
|
||||
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RW, acName8000_01, 0, &Cb.Parameters.Multiplier},
|
||||
};
|
||||
const _objd SDO8001[] =
|
||||
{
|
||||
{0x0, DTYPE_UNSIGNED32, 32, ATYPE_RW, acName8001_0, 0, &Cb.variableRW},
|
||||
};
|
||||
|
||||
const _objectlist SDOobjects[] =
|
||||
{
|
||||
{0x1000, OTYPE_VAR, 0, 0, acName1000, SDO1000},
|
||||
{0x1008, OTYPE_VAR, 0, 0, acName1008, SDO1008},
|
||||
{0x1009, OTYPE_VAR, 0, 0, acName1009, SDO1009},
|
||||
{0x100A, OTYPE_VAR, 0, 0, acName100A, SDO100A},
|
||||
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
|
||||
{0x10F1, OTYPE_RECORD, 2, 0, acName10F1, SDO10F1},
|
||||
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
|
||||
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
|
||||
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
|
||||
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
|
||||
{0x1604, OTYPE_RECORD, 2, 0, acName1604, SDO1604},
|
||||
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
|
||||
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
|
||||
{0x1C00, OTYPE_ARRAY, 4, 0, acName1C00, SDO1C00},
|
||||
{0x1C12, OTYPE_ARRAY, 5, 0, acName1C12, SDO1C12},
|
||||
{0x1C13, OTYPE_ARRAY, 2, 0, acName1C13, SDO1C13},
|
||||
{0x1C32, OTYPE_RECORD, 32, 0, acName1C32, SDO1C32},
|
||||
{0x6005, OTYPE_RECORD, 1, 0, acName6005, SDO6005},
|
||||
{0x6006, OTYPE_RECORD, 1, 0, acName6006, SDO6006},
|
||||
{0x7005, OTYPE_RECORD, 1, 0, acName7005, SDO7005},
|
||||
{0x7006, OTYPE_RECORD, 1, 0, acName7006, SDO7006},
|
||||
{0x7007, OTYPE_RECORD, 1, 0, acName7007, SDO7007},
|
||||
{0x7008, OTYPE_RECORD, 1, 0, acName7008, SDO7008},
|
||||
{0x7009, OTYPE_RECORD, 2, 0, acName7009, SDO7009},
|
||||
{0x8000, OTYPE_RECORD, 1, 0, acName8000, SDO8000},
|
||||
{0x8001, OTYPE_VAR, 0, 0, acName8001, SDO8001},
|
||||
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
|
||||
};
|
||||
#endif
|
|
@ -1,121 +1,50 @@
|
|||
#ifndef __UTYPES_H__
|
||||
#define __UTYPES_H__
|
||||
|
||||
#include <cc.h>
|
||||
#include "cc.h"
|
||||
|
||||
|
||||
/* Object dictionary storage */
|
||||
|
||||
/* Inputs */
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct
|
||||
{
|
||||
CC_PACKED_BEGIN
|
||||
/* Inputs */
|
||||
struct
|
||||
{
|
||||
uint8_t B;
|
||||
} CC_PACKED Button1;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint32_t B;
|
||||
} CC_PACKED Button2;
|
||||
CC_PACKED_END
|
||||
} CC_PACKED _Rbuffer;
|
||||
CC_PACKED_END
|
||||
uint8_t Button1;
|
||||
} Buttons;
|
||||
|
||||
/* Outputs */
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct
|
||||
{
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint32_t LED;
|
||||
} CC_PACKED LEDgroup1;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint8_t LED;
|
||||
} CC_PACKED LEDgroup2;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint8_t LED;
|
||||
} CC_PACKED LEDgroup3;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint8_t LED;
|
||||
} CC_PACKED LEDgroup4;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint8_t LED5;
|
||||
uint8_t LED678;
|
||||
} CC_PACKED LEDgroup5;
|
||||
CC_PACKED_END
|
||||
} CC_PACKED _Wbuffer;
|
||||
CC_PACKED_END
|
||||
|
||||
/* Parameters */
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct
|
||||
{
|
||||
CC_PACKED_BEGIN
|
||||
/* Outputs */
|
||||
struct
|
||||
{
|
||||
uint8_t LED0;
|
||||
} LEDgroup0;
|
||||
|
||||
struct
|
||||
{
|
||||
uint8_t LED1;
|
||||
} LEDgroup1;
|
||||
|
||||
|
||||
/* Parameters */
|
||||
struct
|
||||
{
|
||||
uint32_t Multiplier;
|
||||
} CC_PACKED Parameters;
|
||||
CC_PACKED_END
|
||||
} Parameters;
|
||||
|
||||
uint32_t variableRW;
|
||||
} CC_PACKED _Cbuffer;
|
||||
CC_PACKED_END
|
||||
|
||||
/* Manufacturer specific data */
|
||||
CC_PACKED_BEGIN
|
||||
typedef struct
|
||||
{
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint16_t SyncType;
|
||||
uint32_t CycleTime;
|
||||
uint32_t ShiftTime;
|
||||
uint16_t SyncTypeSupport;
|
||||
uint32_t MinCycleTime;
|
||||
uint32_t CalcCopyTime;
|
||||
uint32_t MinDelayTime;
|
||||
uint16_t GetCycleTime;
|
||||
uint32_t DelayTime;
|
||||
uint32_t Sync0CycleTime;
|
||||
uint16_t SMEventMissedCnt;
|
||||
uint16_t CycleTimeTooSmallCnt;
|
||||
uint16_t ShiftTimeTooSmallCnt;
|
||||
uint16_t RxPDOToggleFailed;
|
||||
uint32_t MinCycleDist;
|
||||
uint32_t MaxCycleDist;
|
||||
uint32_t MinSMSYNCDist;
|
||||
uint32_t MaxSMSYNCDist;
|
||||
uint8_t Dummy_x14;
|
||||
uint8_t SyncError;
|
||||
} CC_PACKED SyncMgrParam;
|
||||
CC_PACKED_END
|
||||
CC_PACKED_BEGIN
|
||||
struct
|
||||
{
|
||||
uint8_t Dummy_x01;
|
||||
uint16_t SyncErrorCounterLimit;
|
||||
} CC_PACKED ErrorSettings;
|
||||
CC_PACKED_END
|
||||
} CC_PACKED _Mbuffer;
|
||||
CC_PACKED_END
|
||||
/* Manufacturer specific data */
|
||||
|
||||
extern _Rbuffer Rb;
|
||||
extern _Wbuffer Wb;
|
||||
extern _Cbuffer Cb;
|
||||
extern _Mbuffer Mb;
|
||||
/* Dynamic TX PDO:s */
|
||||
|
||||
/* Dynamic RX PDO:s */
|
||||
|
||||
/* Sync Managers */
|
||||
|
||||
} _Objects;
|
||||
|
||||
extern _Objects Obj;
|
||||
|
||||
#endif /* __UTYPES_H__ */
|
||||
|
|
Loading…
Reference in New Issue