Merge pull request #32 from nakarlsson/master

Add sync support and extend esc_config for generic stack
pull/35/head v2.0.0
Hans-Erik Floryd 2017-10-30 09:55:44 +01:00 committed by GitHub
commit 4dfb81e548
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
43 changed files with 4934 additions and 1242 deletions

View File

@ -5,8 +5,8 @@ cmake_minimum_required (VERSION 2.8.4)
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake")
project (SOES)
set (SOES_VERSION_MAJOR 1)
set (SOES_VERSION_MINOR 1)
set (SOES_VERSION_MAJOR 2)
set (SOES_VERSION_MINOR 0)
set (SOES_VERSION_PATCH 0)
# Generate version numbers

View File

@ -1,7 +1,8 @@
SOES Simple Open EtherCAT Slave
Copyright (C) 2007-2014 Arthur Ketels
Copyright (C) 2012-2014 rt-labs
Copyright (C) 2007-2017 Arthur Ketels
Copyright (C) 2012-2017 rt-labs
SOES is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License version 2 as published by the Free
Software Foundation.

View File

@ -12,7 +12,7 @@ SOES is an EtherCAT slave stack written in c. Its purpose is to learn and
to use. All users are invited to study the source to get an understanding
how an EtherCAT slave functions.
Features as of 1.1.0:
Features as of 2.0.0:
- Address offset based HAL for easy ESC read/write access via any
interface
- Mailbox with data link layer
@ -22,5 +22,12 @@ Features as of 1.1.0:
- Easy portable C-code suited for embedded applications
- Fixed PDO mapping
- FoE with bootstrap template
- Support for Little and Big endian targets.
- Polling for interrupts
- Support for Little and Big endian targets
- Run polling, mixed polling/interrupt or interrupt
- Support for SM Synchronization
- Support DC sync0 and DC Synchronization
- Add stack configuration via new configuration paramater to/or from
"stack"_init
TODO
- Update documentation

View File

@ -1,38 +1,57 @@
#include <stddef.h>
#include "utypes.h"
#include "soes/esc.h"
#include "soes/esc_coe.h"
#include "soes/esc_foe.h"
#include "esc.h"
#include "esc_coe.h"
#include "esc_foe.h"
#include "config.h"
#include "slave.h"
#ifndef EEP_EMULATION
#define EEP_EMULATION 0 /* Set to 1 for EEPROM emulation */
#endif
#define WATCHDOG_RESET_VALUE 150
#define DEFAULTTXPDOMAP 0x1a00
#define DEFAULTRXPDOMAP 0x1600
#define DEFAULTTXPDOITEMS 1
#define DEFAULTRXPDOITEMS 1
volatile _ESCvar ESCvar;
_MBX MBX[MBXBUFFERS];
_MBXcontrol MBXcontrol[MBXBUFFERS];
uint8_t MBXrun=0;
uint16_t SM2_sml,SM3_sml;
_Rbuffer Rb;
_Wbuffer Wb;
_Cbuffer Cb;
_App App;
uint16_t TXPDOsize,RXPDOsize;
/* 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;
/* Private variables */
uint16_t txpdomap = DEFAULTTXPDOMAP;
uint16_t rxpdomap = DEFAULTRXPDOMAP;
uint8_t txpdoitems = DEFAULTTXPDOITEMS;
uint8_t rxpdoitems = DEFAULTTXPDOITEMS;
static unsigned int watchdog = WATCHDOG_RESET_VALUE;
static int watchdog = WATCHDOG_RESET_VALUE;
static void (*application_loop_callback)(void) = NULL;
/** 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)
{
if ((index == 0x1c12) && (subindex > 0) && (rxpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if ((index == 0x1c13) && (subindex > 0) && (txpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
return 1;
}
/** Mandatory: Hook called from the slave stack SDO Download handler to act on
* user specified Index and Sub-index.
*
@ -54,7 +73,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
rxpdomap = 0x1600;
}
RXPDOsize = SM2_sml = sizeRXPDO();
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
break;
}
case 0x1c13:
@ -68,7 +87,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
txpdomap = 0x1A00;
}
TXPDOsize = SM3_sml = sizeTXPDO();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
break;
}
/* Handle post-write of parameter values */
@ -100,13 +119,13 @@ void APP_safeoutput (void)
*/
void TXPDO_update (void)
{
ESC_write (SM3_sma, &Rb, TXPDOsize);
ESC_write (SM3_sma, &Rb, ESCvar.TXPDOsize);
}
/** Mandatory: Read Sync Manager 2 to local process data, Master Outputs.
*/
void RXPDO_update (void)
{
ESC_read (SM2_sma, &Wb, RXPDOsize);
ESC_read (SM2_sma, &Wb, ESCvar.RXPDOsize);
}
/** Mandatory: Function to update local I/O, call read ethercat outputs, call
@ -119,7 +138,7 @@ void DIG_process (void)
{
watchdog--;
}
if (App.state & APPSTATE_OUTPUT)
if (ESCvar.App.state & APPSTATE_OUTPUT)
{
/* SM2 trigger ? */
if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
@ -131,7 +150,7 @@ void DIG_process (void)
/* Set outputs */
cb_set_LEDs();
}
if (watchdog == 0)
if (watchdog <= 0)
{
DPRINT("DIG_process watchdog expired\n");
ESC_stopoutput();
@ -145,7 +164,7 @@ void DIG_process (void)
{
watchdog = WATCHDOG_RESET_VALUE;
}
if (App.state)
if (ESCvar.App.state)
{
/* Update inputs */
cb_get_Buttons();
@ -155,8 +174,6 @@ void DIG_process (void)
/********** TODO: Generic code beyond this point ***************/
static const char *spi_name = "/dev/lan9252";
/** Optional: Hook called after state change for application specific
* actions for specific state changes.
*/
@ -204,6 +221,8 @@ void soes (void)
/* Check the state machine */
ESC_state();
/* Check the SM activation event */
ESC_sm_act_event();
/* Check mailboxes */
if (ESC_mbxprocess())
@ -213,10 +232,6 @@ void soes (void)
ESC_xoeprocess();
}
DIG_process();
#if EEP_EMULATION
EEP_process ();
EEP_hw_process();
#endif /* EEP_EMULATION */
if (application_loop_callback != NULL)
{
@ -231,19 +246,39 @@ void soes_init (void)
{
DPRINT ("SOES (Simple Open EtherCAT Slave)\n");
TXPDOsize = SM3_sml = sizeTXPDO();
RXPDOsize = SM2_sml = sizeRXPDO();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
/* Setup post config hooks */
/* Setup config hooks */
static esc_cfg_t config =
{
.pre_state_change_hook = NULL,
.post_state_change_hook = post_state_change_hook
.user_arg = "/dev/lan9252",
.use_interrupt = 0,
.watchdog_cnt = 0,
.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 = NULL,
.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 = NULL,
.esc_hw_interrupt_disable = NULL,
.esc_hw_eep_handler = NULL
};
ESC_config ((esc_cfg_t *)&config);
ESC_reset();
ESC_init ((void *)spi_name);
ESC_config (&config);
ESC_init (&config);
/* wait until ESC is started up */
while ((ESCvar.DLstatus & 0x0001) == 0)

View File

@ -1,38 +1,57 @@
#include <stddef.h>
#include "utypes.h"
#include "soes/esc.h"
#include "soes/esc_coe.h"
#include "soes/esc_foe.h"
#include "esc.h"
#include "esc_coe.h"
#include "esc_foe.h"
#include "config.h"
#include "slave.h"
#ifndef EEP_EMULATION
#define EEP_EMULATION 0 /* Set to 1 for EEPROM emulation */
#endif
#define WATCHDOG_RESET_VALUE 150
#define DEFAULTTXPDOMAP 0x1a00
#define DEFAULTRXPDOMAP 0x1600
#define DEFAULTTXPDOITEMS 1
#define DEFAULTRXPDOITEMS 1
volatile _ESCvar ESCvar;
_MBX MBX[MBXBUFFERS];
_MBXcontrol MBXcontrol[MBXBUFFERS];
uint8_t MBXrun=0;
uint16_t SM2_sml,SM3_sml;
_Rbuffer Rb;
_Wbuffer Wb;
_Cbuffer Cb;
_App App;
uint16_t TXPDOsize,RXPDOsize;
/* 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;
/* Private variables */
uint16_t txpdomap = DEFAULTTXPDOMAP;
uint16_t rxpdomap = DEFAULTRXPDOMAP;
uint8_t txpdoitems = DEFAULTTXPDOITEMS;
uint8_t rxpdoitems = DEFAULTTXPDOITEMS;
static unsigned int watchdog = WATCHDOG_RESET_VALUE;
static int watchdog = WATCHDOG_RESET_VALUE;
static void (*application_loop_callback)(void) = NULL;
/** 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)
{
if ((index == 0x1c12) && (subindex > 0) && (rxpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if ((index == 0x1c13) && (subindex > 0) && (txpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
return 1;
}
/** Mandatory: Hook called from the slave stack SDO Download handler to act on
* user specified Index and Sub-index.
*
@ -54,7 +73,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
rxpdomap = 0x1600;
}
RXPDOsize = SM2_sml = sizeRXPDO();
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
break;
}
case 0x1c13:
@ -68,7 +87,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
txpdomap = 0x1A00;
}
TXPDOsize = SM3_sml = sizeTXPDO();
ESCvar.TXPDOsize = ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
break;
}
/* Handle post-write of parameter values */
@ -100,13 +119,13 @@ void APP_safeoutput (void)
*/
void TXPDO_update (void)
{
ESC_write (SM3_sma, &Rb, TXPDOsize);
ESC_write (SM3_sma, &Rb, ESCvar.TXPDOsize);
}
/** Mandatory: Read Sync Manager 2 to local process data, Master Outputs.
*/
void RXPDO_update (void)
{
ESC_read (SM2_sma, &Wb, RXPDOsize);
ESC_read (SM2_sma, &Wb, ESCvar.RXPDOsize);
}
/** Mandatory: Function to update local I/O, call read ethercat outputs, call
@ -119,7 +138,7 @@ void DIG_process (void)
{
watchdog--;
}
if (App.state & APPSTATE_OUTPUT)
if (ESCvar.App.state & APPSTATE_OUTPUT)
{
/* SM2 trigger ? */
if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
@ -131,7 +150,7 @@ void DIG_process (void)
/* Set outputs */
cb_set_LEDs();
}
if (watchdog == 0)
if (watchdog <= 0)
{
DPRINT("DIG_process watchdog expired\n");
ESC_stopoutput();
@ -145,7 +164,7 @@ void DIG_process (void)
{
watchdog = WATCHDOG_RESET_VALUE;
}
if (App.state)
if (ESCvar.App.state)
{
/* Update inputs */
cb_get_Buttons();
@ -155,8 +174,6 @@ void DIG_process (void)
/********** TODO: Generic code beyond this point ***************/
static const char *spi_name = "/spi1/lan9252";
/** Optional: Hook called after state change for application specific
* actions for specific state changes.
*/
@ -213,10 +230,6 @@ void soes (void)
ESC_xoeprocess();
}
DIG_process();
#if EEP_EMULATION
EEP_process ();
EEP_hw_process();
#endif /* EEP_EMULATION */
if (application_loop_callback != NULL)
{
@ -231,19 +244,39 @@ void soes_init (void)
{
DPRINT ("SOES (Simple Open EtherCAT Slave)\n");
TXPDOsize = SM3_sml = sizeTXPDO();
RXPDOsize = SM2_sml = sizeRXPDO();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
/* Setup post config hooks */
/* Setup config hooks */
static esc_cfg_t config =
{
.pre_state_change_hook = NULL,
.post_state_change_hook = post_state_change_hook
.user_arg = "/spi1/lan9252",
.use_interrupt = 0,
.watchdog_cnt = 0,
.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 = NULL,
.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 = NULL,
.esc_hw_interrupt_disable = NULL,
.esc_hw_eep_handler = NULL
};
ESC_config ((esc_cfg_t *)&config);
ESC_reset();
ESC_init ((void *)spi_name);
ESC_config (&config);
ESC_init (&config);
/* wait until ESC is started up */
while ((ESCvar.DLstatus & 0x0001) == 0)

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2015 Arthur Ketels
* Copyright (C) 2012-2015 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <kern.h>

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2015 Arthur Ketels
* Copyright (C) 2012-2015 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#ifndef _bootstrap_

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2015 Arthur Ketels
* Copyright (C) 2012-2015 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <kern.h>

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2015 Arthur Ketels
* Copyright (C) 2012-2015 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <kern.h>

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -40,6 +17,7 @@
#include <esc_coe.h>
#include <esc_foe.h>
#include "utypes.h"
#include "config.h"
#include "bootstrap.h"
#define WD_RESET 1000
@ -51,16 +29,17 @@
uint32_t encoder_scale;
uint32_t encoder_scale_mirror;
volatile _ESCvar ESCvar;
_MBX MBX[MBXBUFFERS];
_MBXcontrol MBXcontrol[MBXBUFFERS];
uint8_t MBXrun=0;
uint16_t SM2_sml,SM3_sml;
_Rbuffer Rb;
_Wbuffer Wb;
_Cbuffer Cb;
_App App;
uint16_t TXPDOsize,RXPDOsize;
/* 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;
/* Private variables */
int wd_cnt = WD_RESET;
volatile uint8_t digoutput;
volatile uint8_t diginput;
@ -72,7 +51,27 @@ uint8_t rxpdoitems = DEFAULTTXPDOITEMS;
extern uint32_t local_boot_state;
static const char *spi_name = "/spi0/et1100";
/** 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)
{
if ((index == 0x1c12) && (subindex > 0) && (rxpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if ((index == 0x1c13) && (subindex > 0) && (txpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
return 1;
}
/** Mandatory: Hook called from the slave stack SDO Download handler to act on
* user specified Index and Sub-index.
@ -95,7 +94,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
rxpdomap = 0x1600;
}
RXPDOsize = SM2_sml = sizeRXPDO ();
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
break;
}
case 0x1c13:
@ -109,7 +108,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
txpdomap = 0x1A00;
}
TXPDOsize = SM3_sml = sizeTXPDO ();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
break;
}
case 0x7100:
@ -152,13 +151,13 @@ void APP_safeoutput (void)
*/
void TXPDO_update (void)
{
ESC_write (SM3_sma, &Rb.button, TXPDOsize);
ESC_write (SM3_sma, &Rb.button, ESCvar.TXPDOsize);
}
/** Mandatory: Read Sync Manager 2 to local process data, Master Outputs.
*/
void RXPDO_update (void)
{
ESC_read (SM2_sma, &Wb.LED, RXPDOsize);
ESC_read (SM2_sma, &Wb.LED, ESCvar.RXPDOsize);
}
/** Mandatory: Function to update local I/O, call read ethercat outputs, call
@ -171,7 +170,7 @@ void DIG_process (void)
{
wd_cnt--;
}
if (App.state & APPSTATE_OUTPUT)
if (ESCvar.App.state & APPSTATE_OUTPUT)
{
/* SM2 trigger ? */
if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
@ -196,7 +195,7 @@ void DIG_process (void)
{
wd_cnt = WD_RESET;
}
if (App.state)
if (ESCvar.App.state)
{
//Rb.button = gpio_get(GPIO_WAKEUP);
Rb.button = (flash_drv_get_active_swap() && 0x8);
@ -232,19 +231,39 @@ void soes (void *arg)
{
DPRINT ("SOES (Simple Open EtherCAT Slave)\n");
TXPDOsize = SM3_sml = sizeTXPDO ();
RXPDOsize = SM2_sml = sizeRXPDO ();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
/* Setup post config hooks */
/* Setup config hooks */
static esc_cfg_t config =
{
.pre_state_change_hook = NULL,
.post_state_change_hook = post_state_change_hook
.user_arg = "/spi0/et1100",
.use_interrupt = 0,
.watchdog_cnt = 0,
.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 = NULL,
.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 = NULL,
.esc_hw_interrupt_disable = NULL,
.esc_hw_eep_handler = NULL
};
ESC_config ((esc_cfg_t *)&config);
ESC_reset();
ESC_init (spi_name);
ESC_config (&config);
ESC_init (&config);
task_delay (tick_from_ms (200));

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,16 +1,17 @@
#ifndef __CONFIG_H__
#define __CONFIG_H__
#ifndef __config_h__
#define __config_h__
#include <cc.h>
#define MBXSIZE 0x80
#define MBXSIZEBOOT 0x80
#define MBXSIZE 128
#define MBXSIZEBOOT 256
#define MBXBUFFERS 3
#define MBX0_sma 0x1000
#define MBX0_sml MBXSIZE
#define MBX0_sme MBX0_sma+MBX0_sml-1
#define MBX0_smc 0x26
#define MBX1_sma 0x1080
#define MBX1_sma MBX0_sma+MBX0_sml
#define MBX1_sml MBXSIZE
#define MBX1_sme MBX1_sma+MBX1_sml-1
#define MBX1_smc 0x22
@ -19,16 +20,16 @@
#define MBX0_sml_b MBXSIZEBOOT
#define MBX0_sme_b MBX0_sma_b+MBX0_sml_b-1
#define MBX0_smc_b 0x26
#define MBX1_sma_b 0x1080
#define MBX1_sma_b MBX0_sma_b+MBX0_sml_b
#define MBX1_sml_b MBXSIZEBOOT
#define MBX1_sme_b MBX1_sma_b+MBX1_sml_b-1
#define MBX1_smc_b 0x22
#define SM2_sma 0x1100
#define SM2_smc 0x24
#define SM2_act 0x01
#define SM2_act 1
#define SM3_sma 0x1180
#define SM3_smc 0x20
#define SM3_act 0x01
#define SM3_act 1
#endif
#endif /* __CONFIG_H__ */

View File

@ -0,0 +1,184 @@
#include <kern.h>
#include <xmc4.h>
#include <bsp.h>
#include "slave.h"
#include "esc_hw.h"
#include "config.h"
#define SAMPLE_CODE 0
/**
* This function reads physical input values and assigns the corresponding members
* of Rb.Buttons
*/
void cb_get_Buttons()
{
Rb.Buttons.Button1 = gpio_get(GPIO_BUTTON1);
}
/**
* This function writes physical output values from the corresponding members of
* Wb.LEDs
*/
void cb_set_LEDgroup0()
{
gpio_set(GPIO_LED1, Wb.LEDgroup0.LED0);
}
/**
* This function writes physical output values from the corresponding members of
* Wb.LEDs
*/
void cb_set_LEDgroup1()
{
gpio_set(GPIO_LED2, Wb.LEDgroup1.LED1);
}
/**
* This function is called after a SDO write of the object Cb.Parameters.
*/
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)
{
}
/** Optional: Hook called after state change for application specific
* actions for specific state changes.
*/
void post_state_change_hook (uint8_t * as, uint8_t * an)
{
#if SAMPLE_CODE
/* Add specific step change hooks here */
if ((*as == BOOT_TO_INIT) && (*an == ESCinit))
{
rprintf("boot BOOT_TO_INIT\n");
upgrade_finished();
/* If we return here */
ESC_ALerror (ALERR_NOVALIDFIRMWARE);
/* Upgrade failed, enter init with error */
*an = (ESCinit | ESCerror);
}
else if((*as == PREOP_TO_SAFEOP))
{
rprintf("boot PREOP_TO_SAFEOP\n");
ESC_ALerror (ALERR_NOVALIDFIRMWARE);
/* Stay in preop with error bit set */
*an = (ESCpreop | ESCerror);
}
#endif
}
void user_post_dl_objecthandler (uint16_t index, uint8_t subindex)
{
#if SAMPLE_CODE
switch (index)
{
case 0x1c12:
{
RXPDOsize = ESC_SM2_sml = sizeRXPDO();
break;
}
/* Handle post-write of parameter values */
default:
break;
}
#endif
}
int user_pre_dl_objecthandler (uint16_t index, uint8_t subindex)
{
#if SAMPLE_CODE
if (index == 0x1c12)
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if (index == 0x1c13)
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
#endif
return 1;
}
/* Called from stack when stopping outputs */
void user_safeoutput (void)
{
#if SAMPLE_CODE
DPRINT ("APP_safeoutput\n");
// Set safe values for Wb.LEDgroup0
Wb.LEDgroup0.LED0 = 1;
// Set safe values for Wb.LEDgroup1
Wb.LEDgroup1.LED1 = 1;
#endif
}
/* 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 = 100,
.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 = NULL,
.post_state_change_hook = NULL,
.application_hook = NULL,
.safeoutput_override = user_safeoutput,
.pre_object_download_hook = user_pre_dl_objecthandler,
.post_object_download_hook = user_post_dl_objecthandler,
.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
};
void main_run(void * arg)
{
ecat_slv_init(&config);
while(1)
{
if(config.use_interrupt != 0)
{
DIG_process(DIG_PROCESS_WD_FLAG);
}
else
{
ecat_slv();
}
task_delay(1);
}
}
int main(void)
{
rprintf("Hello Main\n");
task_spawn ("soes", main_run, 8, 2048, NULL);
return 0;
}

Binary file not shown.

View File

@ -0,0 +1,327 @@
#ifndef SOES_V1
#include <stddef.h>
#include "utypes.h"
#include "esc.h"
#include "esc_coe.h"
#include "esc_foe.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 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.LEDgroup0
Wb.LEDgroup0.LED0 = 0;
// Set safe values for Wb.LEDgroup1
Wb.LEDgroup1.LED1 = 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_LEDgroup0();
cb_set_LEDgroup1();
}
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_Buttons();
TXPDO_update();
}
}
}
/**
* 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)
{
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 & (ESCREG_ALEVENT_CONTROL | ESCREG_ALEVENT_SMCHANGE
| ESCREG_ALEVENT_SM0 | ESCREG_ALEVENT_SM1 | ESCREG_ALEVENT_EEP));
ESC_ALeventmaskwrite(ESC_ALeventmaskread()
| (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_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

View File

@ -0,0 +1,739 @@
<?xml version="1.0" encoding="UTF-8"?>
<Slave fileVersion="1" id="xmc43_slave" productCode="4300">
<Name>xmc43relax</Name>
<Vendor>
<Id>0x1337</Id>
<Name>rt-labs</Name>
</Vendor>
<Group>
<Type>xmc4</Type>
<Name>xmc4</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="0x24" DefaultSize="0" StartAddress="0x1100">Outputs</Sm>
<Sm ControlByte="0x20" DefaultSize="0" StartAddress="0x1180">Inputs</Sm>
<Mailbox CoE="true" FoE="true">
<Bootstrap Length="256" Start="0x1000"/>
<Standard Length="128" Start="0x1000"/>
</Mailbox>
<Eeprom>
<ConfigData>8006810600000000</ConfigData>
<BootStrap>0010000100110001</BootStrap>
</Eeprom>
<Dictionary>
<Item>
<Name>Device Type</Name>
<Index>0x1000</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x00001389</DefaultValue>
</Item>
<Item Managed="true">
<Name>Device Name</Name>
<Index>0x1008</Index>
<DataType>VISIBLE_STRING</DataType>
<DefaultValue>xmc43_slave</DefaultValue>
</Item>
<Item>
<Name>Hardware Version</Name>
<Index>0x1009</Index>
<DataType>VISIBLE_STRING</DataType>
<DefaultValue>1.0</DefaultValue>
</Item>
<Item>
<Name>Software Version</Name>
<Index>0x100A</Index>
<DataType>VISIBLE_STRING</DataType>
<DefaultValue>1.0</DefaultValue>
</Item>
<Item Managed="true">
<Name>Identity Object</Name>
<Index>0x1018</Index>
<DataType>RECORD</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>4</DefaultValue>
</SubItem>
<SubItem>
<Name>Vendor ID</Name>
<Index>0x01</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x1337</DefaultValue>
</SubItem>
<SubItem>
<Name>Product Code</Name>
<Index>0x02</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>4300</DefaultValue>
</SubItem>
<SubItem>
<Name>Revision Number</Name>
<Index>0x03</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
</SubItem>
<SubItem>
<Name>Serial Number</Name>
<Index>0x04</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x00000000</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>ErrorSettings</Name>
<Index>0x10F1</Index>
<DataType>RECORD</DataType>
<Variable>ErrorSettings</Variable>
<VariableType>Manufacturer</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>2</DefaultValue>
</SubItem>
<SubItem>
<Name>Dummy_x01</Name>
<Index>0x01</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>Dummy_x01</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>SyncErrorCounterLimit</Name>
<Index>0x02</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>2</DefaultValue>
<Access>RW</Access>
<Variable>SyncErrorCounterLimit</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>LEDgroup0</Name>
<Index>0x1600</Index>
<DataType>RECORD</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>LED0</Name>
<Index>0x01</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x70050108</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>LEDgroup1</Name>
<Index>0x1601</Index>
<DataType>RECORD</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>LED1</Name>
<Index>0x01</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x70060108</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>Buttons</Name>
<Index>0x1A00</Index>
<DataType>RECORD</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>Button1</Name>
<Index>0x01</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0x60050108</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>Sync Manager Communication Type</Name>
<Index>0x1C00</Index>
<DataType>ARRAY</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>4</DefaultValue>
</SubItem>
<SubItem>
<Name>Communications Type SM0</Name>
<Index>0x01</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>Communications Type SM1</Name>
<Index>0x02</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>2</DefaultValue>
</SubItem>
<SubItem>
<Name>Communications Type SM2</Name>
<Index>0x03</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>3</DefaultValue>
</SubItem>
<SubItem>
<Name>Communications Type SM3</Name>
<Index>0x04</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>4</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>Sync Manager 2 PDO Assignment</Name>
<Index>0x1C12</Index>
<DataType>ARRAY</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>2</DefaultValue>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Index>0x01</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0x1600</DefaultValue>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Index>0x02</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0x1601</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>Sync Manager 3 PDO Assignment</Name>
<Index>0x1C13</Index>
<DataType>ARRAY</DataType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>PDO Mapping</Name>
<Index>0x01</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0x1A00</DefaultValue>
</SubItem>
</Item>
<Item Managed="true">
<Name>SyncMgrParam</Name>
<Index>0x1C32</Index>
<DataType>RECORD</DataType>
<Variable>SyncMgrParam</Variable>
<VariableType>Manufacturer</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>32</DefaultValue>
</SubItem>
<SubItem>
<Name>SyncType</Name>
<Index>0x01</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>1</DefaultValue>
<Access>RO</Access>
<Variable>SyncType</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>CycleTime</Name>
<Index>0x02</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>CycleTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>ShiftTime</Name>
<Index>0x03</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>ShiftTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>SyncTypeSupport</Name>
<Index>0x04</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0x6</DefaultValue>
<Access>RO</Access>
<Variable>SyncTypeSupport</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MinCycleTime</Name>
<Index>0x05</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>125000</DefaultValue>
<Access>RO</Access>
<Variable>MinCycleTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>CalcCopyTime</Name>
<Index>0x06</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>CalcCopyTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MinDelayTime</Name>
<Index>0x07</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>MinDelayTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>GetCycleTime</Name>
<Index>0x08</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>GetCycleTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>DelayTime</Name>
<Index>0x09</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>DelayTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>Sync0CycleTime</Name>
<Index>0x0A</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>Sync0CycleTime</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>SMEventMissedCnt</Name>
<Index>0x0B</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>SMEventMissedCnt</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>CycleTimeTooSmallCnt</Name>
<Index>0x0C</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>CycleTimeTooSmallCnt</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>ShiftTimeTooSmallCnt</Name>
<Index>0x0D</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>ShiftTimeTooSmallCnt</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>RxPDOToggleFailed</Name>
<Index>0x0E</Index>
<DataType>UNSIGNED16</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>RxPDOToggleFailed</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MinCycleDist</Name>
<Index>0x0F</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>MinCycleDist</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MaxCycleDist</Name>
<Index>0x10</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>MaxCycleDist</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MinSMSYNCDist</Name>
<Index>0x11</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>MinSMSYNCDist</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>MaxSMSYNCDist</Name>
<Index>0x12</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>MaxSMSYNCDist</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>Dummy_x14</Name>
<Index>0x14</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>Dummy_x14</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
<SubItem>
<Name>SyncError</Name>
<Index>0x20</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>SyncError</Variable>
<VariableType>Manufacturer</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>Buttons</Name>
<Index>0x6005</Index>
<DataType>RECORD</DataType>
<Variable>Buttons</Variable>
<VariableType>Input</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>Button1</Name>
<Index>0x01</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>Button1</Variable>
<VariableType>Input</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>LEDgroup0</Name>
<Index>0x7005</Index>
<DataType>RECORD</DataType>
<Variable>LEDgroup0</Variable>
<VariableType>Output</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>LED0</Name>
<Index>0x01</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>LED0</Variable>
<VariableType>Output</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>LEDgroup1</Name>
<Index>0x7006</Index>
<DataType>RECORD</DataType>
<Variable>LEDgroup1</Variable>
<VariableType>Output</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>LED1</Name>
<Index>0x01</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>0</DefaultValue>
<Access>RO</Access>
<Variable>LED1</Variable>
<VariableType>Output</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>Parameters</Name>
<Index>0x8000</Index>
<DataType>RECORD</DataType>
<Variable>Parameters</Variable>
<VariableType>Parameter</VariableType>
<SubItem>
<Name>Max SubIndex</Name>
<Index>0x00</Index>
<DataType>UNSIGNED8</DataType>
<DefaultValue>1</DefaultValue>
</SubItem>
<SubItem>
<Name>Multiplier</Name>
<Index>0x01</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RW</Access>
<Variable>Multiplier</Variable>
<VariableType>Parameter</VariableType>
</SubItem>
</Item>
<Item Managed="true">
<Name>variableRW</Name>
<Index>0x8001</Index>
<DataType>UNSIGNED32</DataType>
<DefaultValue>0</DefaultValue>
<Access>RW</Access>
<Variable>variableRW</Variable>
<VariableType>Parameter</VariableType>
</Item>
</Dictionary>
<RxPdo>
<Index>0x1600</Index>
<Container>LEDgroup0</Container>
<Name>LEDgroup0</Name>
<Entry>
<Index>0x7005</Index>
<SubIndex>1</SubIndex>
<Variable>LED0</Variable>
</Entry>
</RxPdo>
<RxPdo>
<Index>0x1601</Index>
<Container>LEDgroup1</Container>
<Name>LEDgroup1</Name>
<Entry>
<Index>0x7006</Index>
<SubIndex>1</SubIndex>
<Variable>LED1</Variable>
</Entry>
</RxPdo>
<TxPdo>
<Index>0x1A00</Index>
<Container>Buttons</Container>
<Name>Buttons</Name>
<Entry>
<Index>0x6005</Index>
<SubIndex>1</SubIndex>
<Variable>Button1</Variable>
</Entry>
</TxPdo>
<Input>
<Index>0x6005</Index>
<Name>Buttons</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>Button1</Name>
<Type>UNSIGNED8</Type>
</Member>
</Input>
<Output>
<Index>0x7005</Index>
<Name>LEDgroup0</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>LED0</Name>
<Type>UNSIGNED8</Type>
</Member>
</Output>
<Output>
<Index>0x7006</Index>
<Name>LEDgroup1</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>LED1</Name>
<Type>UNSIGNED8</Type>
</Member>
</Output>
<Parameter>
<Index>0x8000</Index>
<Name>Parameters</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>Multiplier</Name>
<Type>UNSIGNED32</Type>
<Access>RW</Access>
</Member>
</Parameter>
<Parameter>
<Index>0x8001</Index>
<Name>variableRW</Name>
<Type>UNSIGNED32</Type>
<Access>RW</Access>
<ObjectType>VAR</ObjectType>
</Parameter>
<Manufacturer>
<Index>0x1C32</Index>
<Name>SyncMgrParam</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>SyncType</Name>
<Type>UNSIGNED16</Type>
<DefaultValue>1</DefaultValue>
</Member>
<Member>
<Index>0x02</Index>
<Name>CycleTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x03</Index>
<Name>ShiftTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x04</Index>
<Name>SyncTypeSupport</Name>
<Type>UNSIGNED16</Type>
<DefaultValue>0x6</DefaultValue>
</Member>
<Member>
<Index>0x05</Index>
<Name>MinCycleTime</Name>
<Type>UNSIGNED32</Type>
<DefaultValue>125000</DefaultValue>
</Member>
<Member>
<Index>0x06</Index>
<Name>CalcCopyTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x07</Index>
<Name>MinDelayTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x08</Index>
<Name>GetCycleTime</Name>
<Type>UNSIGNED16</Type>
</Member>
<Member>
<Index>0x09</Index>
<Name>DelayTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x0A</Index>
<Name>Sync0CycleTime</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x0B</Index>
<Name>SMEventMissedCnt</Name>
<Type>UNSIGNED16</Type>
</Member>
<Member>
<Index>0x0C</Index>
<Name>CycleTimeTooSmallCnt</Name>
<Type>UNSIGNED16</Type>
</Member>
<Member>
<Index>0x0D</Index>
<Name>ShiftTimeTooSmallCnt</Name>
<Type>UNSIGNED16</Type>
</Member>
<Member>
<Index>0x0E</Index>
<Name>RxPDOToggleFailed</Name>
<Type>UNSIGNED16</Type>
</Member>
<Member>
<Index>0x0F</Index>
<Name>MinCycleDist</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x10</Index>
<Name>MaxCycleDist</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x11</Index>
<Name>MinSMSYNCDist</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x12</Index>
<Name>MaxSMSYNCDist</Name>
<Type>UNSIGNED32</Type>
</Member>
<Member>
<Index>0x14</Index>
<Name>Dummy_x14</Name>
<Type>UNSIGNED8</Type>
</Member>
<Member>
<Index>0x20</Index>
<Name>SyncError</Name>
<Type>UNSIGNED8</Type>
<Access>RO</Access>
</Member>
</Manufacturer>
<Manufacturer>
<Index>0x10F1</Index>
<Name>ErrorSettings</Name>
<ObjectType>RECORD</ObjectType>
<Member>
<Index>0x01</Index>
<Name>Dummy_x01</Name>
<Type>UNSIGNED8</Type>
</Member>
<Member>
<Index>0x02</Index>
<Name>SyncErrorCounterLimit</Name>
<Type>UNSIGNED16</Type>
<DefaultValue>2</DefaultValue>
<Access>RW</Access>
</Member>
</Manufacturer>
</Slave>

View File

@ -0,0 +1,64 @@
#ifndef __SLAVE_H__
#define __SLAVE_H__
#include "utypes.h"
#include "esc.h"
/**
* This function gets input values and updates Rb.Buttons
*/
void cb_get_Buttons();
/**
* This function sets output values according to Wb.LEDgroup0
*/
void cb_set_LEDgroup0();
/**
* This function sets output values according to Wb.LEDgroup1
*/
void cb_set_LEDgroup1();
/**
* 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);
/**
* ISR for SM0/1, EEPROM and AL CONTROL events in a SM/DC
* synchronization application
*/
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

View File

@ -0,0 +1,218 @@
#ifndef SOES_V1
#include "esc_coe.h"
#include "utypes.h"
#include <stddef.h>
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[] = "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 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[] = "Buttons";
static const char acName6005_00[] = "Max SubIndex";
static const char acName6005_01[] = "Button1";
static const char acName7005[] = "LEDgroup0";
static const char acName7005_00[] = "Max SubIndex";
static const char acName7005_01[] = "LED0";
static const char acName7006[] = "LEDgroup1";
static const char acName7006_00[] = "Max SubIndex";
static const char acName7006_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";
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, "xmc43_slave"},
};
const _objd SDO1009[] =
{
{0x0, DTYPE_VISIBLE_STRING, 24, ATYPE_RO, acName1009_0, 0, "1.0"},
};
const _objd SDO100A[] =
{
{0x0, DTYPE_VISIBLE_STRING, 24, ATYPE_RO, acName100A_0, 0, "1.0"},
};
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, 4300, 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, 0x70050108, 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 SDO1A00[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1A00_00, 1, NULL},
{0x01, DTYPE_UNSIGNED32, 32, ATYPE_RO, acName1A00_01, 0x60050108, 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 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.Buttons.Button1},
};
const _objd SDO7005[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7005_00, 1, NULL},
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7005_01, 0, &Wb.LEDgroup0.LED0},
};
const _objd SDO7006[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7006_00, 1, NULL},
{0x01, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7006_01, 0, &Wb.LEDgroup1.LED1},
};
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},
{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},
{0x1C32, OTYPE_RECORD, 32, 0, acName1C32, SDO1C32},
{0x6005, OTYPE_RECORD, 1, 0, acName6005, SDO6005},
{0x7005, OTYPE_RECORD, 1, 0, acName7005, SDO7005},
{0x7006, OTYPE_RECORD, 1, 0, acName7006, SDO7006},
{0x8000, OTYPE_RECORD, 1, 0, acName8000, SDO8000},
{0x8001, OTYPE_VAR, 0, 0, acName8001, SDO8001},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};
#endif

View File

@ -0,0 +1,96 @@
#ifndef __UTYPES_H__
#define __UTYPES_H__
#include <cc.h>
/* Inputs */
CC_PACKED_BEGIN
typedef struct
{
CC_PACKED_BEGIN
struct
{
uint8_t Button1;
} CC_PACKED Buttons;
CC_PACKED_END
} CC_PACKED _Rbuffer;
CC_PACKED_END
/* Outputs */
CC_PACKED_BEGIN
typedef struct
{
CC_PACKED_BEGIN
struct
{
uint8_t LED0;
} CC_PACKED LEDgroup0;
CC_PACKED_END
CC_PACKED_BEGIN
struct
{
uint8_t LED1;
} CC_PACKED LEDgroup1;
CC_PACKED_END
} CC_PACKED _Wbuffer;
CC_PACKED_END
/* Parameters */
CC_PACKED_BEGIN
typedef struct
{
CC_PACKED_BEGIN
struct
{
uint32_t Multiplier;
} CC_PACKED Parameters;
CC_PACKED_END
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
extern _Rbuffer Rb;
extern _Wbuffer Wb;
extern _Cbuffer Cb;
extern _Mbuffer Mb;
#endif /* __UTYPES_H__ */

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -64,17 +41,17 @@ static const XMC_GPIO_CONFIG_t gpio_config_led = {
uint32_t encoder_scale;
uint32_t encoder_scale_mirror;
volatile _ESCvar ESCvar;
_MBX MBX[MBXBUFFERS];
_MBXcontrol MBXcontrol[MBXBUFFERS];
uint8_t MBXrun=0;
uint16_t SM2_sml,SM3_sml;
_Rbuffer Rb;
_Wbuffer Wb;
_Cbuffer Cb;
_App App;
uint16_t TXPDOsize,RXPDOsize;
int wd_cnt = WD_RESET;
/* 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;
/* Private variables */
volatile uint8_t digoutput;
volatile uint8_t diginput;
uint16_t txpdomap = DEFAULTTXPDOMAP;
@ -82,6 +59,28 @@ uint16_t rxpdomap = DEFAULTRXPDOMAP;
uint8_t txpdoitems = DEFAULTTXPDOITEMS;
uint8_t rxpdoitems = DEFAULTTXPDOITEMS;
/** 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)
{
if ((index == 0x1c12) && (subindex > 0) && (rxpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if ((index == 0x1c13) && (subindex > 0) && (txpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
return 1;
}
/** Mandatory: Hook called from the slave stack SDO Download handler to act on
* user specified Index and Sub-index.
*
@ -103,7 +102,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
rxpdomap = 0x1600;
}
RXPDOsize = SM2_sml = sizeRXPDO ();
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
break;
}
case 0x1c13:
@ -117,7 +116,7 @@ void ESC_objecthandler (uint16_t index, uint8_t subindex)
{
txpdomap = 0x1A00;
}
TXPDOsize = SM3_sml = sizeTXPDO ();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
break;
}
case 0x7100:
@ -160,13 +159,13 @@ void APP_safeoutput (void)
*/
void TXPDO_update (void)
{
ESC_write (SM3_sma, &Rb.button, TXPDOsize);
ESC_write (SM3_sma, &Rb.button, ESCvar.TXPDOsize);
}
/** Mandatory: Read Sync Manager 2 to local process data, Master Outputs.
*/
void RXPDO_update (void)
{
ESC_read (SM2_sma, &Wb.LED, RXPDOsize);
ESC_read (SM2_sma, &Wb.LED, ESCvar.RXPDOsize);
}
/** Mandatory: Function to update local I/O, call read ethercat outputs, call
@ -179,7 +178,7 @@ void DIG_process (void)
{
wd_cnt--;
}
if (App.state & APPSTATE_OUTPUT)
if (ESCvar.App.state & APPSTATE_OUTPUT)
{
/* SM2 trigger ? */
if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
@ -208,7 +207,7 @@ void DIG_process (void)
{
wd_cnt = WD_RESET;
}
if (App.state)
if (ESCvar.App.state)
{
Rb.button = XMC_GPIO_GetInput(P_BTN);
Cb.reset_counter++;
@ -231,17 +230,38 @@ void soes_init (void)
XMC_GPIO_Init(P_BTN, &gpio_config_btn);
XMC_GPIO_Init(P_LED, &gpio_config_led);
TXPDOsize = SM3_sml = sizeTXPDO ();
RXPDOsize = SM2_sml = sizeRXPDO ();
ESCvar.TXPDOsize = ESCvar.ESC_SM3_sml = sizeOfPDO(TX_PDO_OBJIDX);
ESCvar.RXPDOsize = ESCvar.ESC_SM2_sml = sizeOfPDO(RX_PDO_OBJIDX);
/* Setup post config hooks */
/* Setup config hooks */
static esc_cfg_t config =
{
.pre_state_change_hook = NULL,
.post_state_change_hook = NULL
.user_arg = NULL,
.use_interrupt = 0,
.watchdog_cnt = 0,
.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 = NULL,
.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 = NULL,
.esc_hw_interrupt_disable = NULL,
.esc_hw_eep_handler = NULL
};
ESC_config ((esc_cfg_t *)&config);
ESC_config (&config);
ESC_init (NULL);
/* wait until ESC is started up */
@ -274,7 +294,9 @@ void soes_task (void)
ESCvar.Time = etohl (ESCvar.Time);
/* Check the state machine */
ESC_state ();
ESC_state();
/* Check the SM activation event */
ESC_sm_act_event();
/* If else to two separate execution paths
* If we're running BOOSTRAP

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <string.h>
#include <cc.h>
@ -39,7 +15,6 @@
*
* State machine and mailbox support.
*/
static esc_cfg_t * esc_cfg = NULL;
/** Write AL Status Code to the ESC.
*
@ -52,6 +27,7 @@ void ESC_ALerror (uint16_t errornumber)
dummy = htoes (errornumber);
ESC_write (ESCREG_ALERROR, &dummy, sizeof (dummy));
}
/** Write AL Status to the ESC.
*
* @param[in] status = Write current slave status to register 0x130 AL Status
@ -65,6 +41,51 @@ void ESC_ALstatus (uint8_t status)
ESC_write (ESCREG_ALSTATUS, &dummy, sizeof (dummy));
}
/** Write ALeventMask register 0x204.
*
* @param[in] n = AL Event Mask
*/
void ESC_ALeventmaskwrite (uint32_t mask)
{
uint32_t aleventmask;
aleventmask = htoel(mask);
ESC_write (ESCREG_ALEVENTMASK, &aleventmask, sizeof(aleventmask));
}
/** Read AleventMask register 0x204.
*
* @return value of register AL Event Mask
*/
uint32_t ESC_ALeventmaskread (void)
{
uint32_t aleventmask;
ESC_read (ESCREG_ALEVENTMASK, &aleventmask, sizeof(aleventmask));
return htoel(aleventmask);
}
/** Write ALevent register 0x220.
*
* @param[in] n = AL Event Mask
*/
void ESC_ALeventwrite (uint32_t event)
{
uint32_t alevent;
alevent = htoel(event);
ESC_write (ESCREG_ALEVENT, &alevent, sizeof(alevent));
}
/** Read Alevent register 0x220.
*
* @return value of register AL Event Mask
*/
uint32_t ESC_ALeventread (void)
{
uint32_t alevent;
ESC_read (ESCREG_ALEVENT, &alevent, sizeof(alevent));
return htoel(alevent);
}
/** Read SM Status register 0x805(+ offset to SyncManager n) to acknowledge a
* Sync Manager event Bit 3 in ALevent. The result is not used.
*
@ -152,6 +173,107 @@ uint8_t ESC_WDstatus (void)
return (uint8_t) wdstatus;
}
/** Read SYNC Out Unit activation registers 0x981
*
* @return value of register Activation.
*/
uint8_t ESC_SYNCactivation (void)
{
uint8_t activation;
ESC_read (ESCREG_SYNC_ACT, &activation, sizeof(activation));
return activation;
}
/** Read SYNC0 cycle time
*
* @return value of register SYNC0 cycle time
*/
uint32_t ESC_SYNC0cycletime (void)
{
uint32_t cycletime;
ESC_read (ESCREG_SYNC0_CYCLE_TIME, &cycletime, sizeof(cycletime));
cycletime = etohl (cycletime);
return cycletime;
}
/** Read SYNC1 cycle time
*
* @return value of register SYNC1 cycle time
*/
uint32_t ESC_SYNC1cycletime (void)
{
uint32_t cycletime;
ESC_read (ESCREG_SYNC1_CYCLE_TIME, &cycletime, 4);
cycletime = etohl (cycletime);
return cycletime;
}
/** Validate the DC values if the SYNC unit is activated.
*
* @return = 0 if OK, else ERROR code to be set by caller.
*/
uint16_t ESC_checkDC (void)
{
uint16_t ret = 0;
uint8_t sync_act = ESC_SYNCactivation();
uint32_t sync0_cycletime = ESC_SYNC0cycletime();
uint16_t sync_type_supported1c32 = 0;
uint32_t mincycletime = 0;
/* Do we need to check sync settings? */
if((sync_act & (ESCREG_SYNC_ACT_ACTIVATED | ESCREG_SYNC_AUTO_ACTIVATED)) > 0)
{
/* If the sync unit is active at least on signal should be activated */
if(COE_getSyncMgrPara(0x1c32, 0x4, &sync_type_supported1c32, DTYPE_UNSIGNED16) == 0)
{
ret = ALERR_DCINVALIDSYNCCFG;
}
else if(COE_getSyncMgrPara(0x1c32, 0x5, &mincycletime, DTYPE_UNSIGNED32) == 0)
{
ret = ALERR_DCINVALIDSYNCCFG;
}
else if(COE_getSyncMgrPara(0x10F1, 0x2, &ESCvar.synccounterlimit, DTYPE_UNSIGNED16) == 0)
{
ret = ALERR_DCINVALIDSYNCCFG;
}
else if((sync_act & (ESCREG_SYNC_SYNC0_EN | ESCREG_SYNC_SYNC1_EN)) == 0)
{
ret = ALERR_DCINVALIDSYNCCFG;
}
/* Do we support activated signals */
else if(((sync_type_supported1c32 & SYNCTYPE_SUPPORT_DCSYNC0) == 0) &&
((sync_act & ESCREG_SYNC_SYNC0_EN) > 0))
{
ret = ALERR_DCINVALIDSYNCCFG;
}
/* Do we support activated signals */
else if(((sync_type_supported1c32 & SYNCTYPE_SUPPORT_DCSYNC1) == 0) &&
((sync_act & ESCREG_SYNC_SYNC1_EN) > 0))
{
ret = ALERR_DCINVALIDSYNCCFG;
}
else if((sync0_cycletime != 0) && (sync0_cycletime < mincycletime))
{
ret = ALERR_DCSYNC0CYCLETIME;
}
else
{
ESCvar.dcsync = 1;
ESCvar.synccounter = 0;
}
}
else
{
ESCvar.dcsync = 0;
ESCvar.synccounter = 0;
}
return ret;
}
/** Check mailbox status by reading all SyncManager 0 and 1 data. The read values
* are compared with local definitions for SM Physical Address, SM Length and SM Control.
* If we check fails we disable Mailboxes by disabling SyncManager 0 and 1 and return
@ -167,8 +289,8 @@ uint8_t ESC_checkmbx (uint8_t state)
ESC_read (ESCREG_SM0, (void *) &ESCvar.SM[0], sizeof (ESCvar.SM[0]));
ESC_read (ESCREG_SM1, (void *) &ESCvar.SM[1], sizeof (ESCvar.SM[1]));
SM = (_ESCsm2 *) & ESCvar.SM[0];
if ((etohs (SM->PSA) != MBX0_sma) || (etohs (SM->Length) != MBX0_sml)
|| (SM->Command != MBX0_smc) || (ESCvar.SM[0].ECsm == 0))
if ((etohs (SM->PSA) != ESC_MBX0_sma) || (etohs (SM->Length) != ESC_MBX0_sml)
|| (SM->Command != ESC_MBX0_smc) || (ESCvar.SM[0].ECsm == 0))
{
ESCvar.SMtestresult = SMRESULT_ERRSM0;
ESC_SMdisable (0);
@ -176,8 +298,8 @@ uint8_t ESC_checkmbx (uint8_t state)
return (uint8_t) (ESCinit | ESCerror); //fail state change
}
SM = (_ESCsm2 *) & ESCvar.SM[1];
if ((etohs (SM->PSA) != MBX1_sma) || (etohs (SM->Length) != MBX1_sml)
|| (SM->Command != MBX1_smc) || (ESCvar.SM[1].ECsm == 0))
if ((etohs (SM->PSA) != ESC_MBX1_sma) || (etohs (SM->Length) != ESC_MBX1_sml)
|| (SM->Command != ESC_MBX1_smc) || (ESCvar.SM[1].ECsm == 0))
{
ESCvar.SMtestresult = SMRESULT_ERRSM1;
ESC_SMdisable (0);
@ -197,6 +319,12 @@ uint8_t ESC_checkmbx (uint8_t state)
*/
uint8_t ESC_startmbx (uint8_t state)
{
/* Assign SM settings */
ESCvar.activembxsize = ESCvar.mbxsize;
ESCvar.activemb0 = &ESCvar.mb[0];
ESCvar.activemb1 = &ESCvar.mb[1];
ESC_SMenable (0);
ESC_SMenable (1);
ESC_SMstatus (0);
@ -204,46 +332,12 @@ uint8_t ESC_startmbx (uint8_t state)
if ((state = ESC_checkmbx (state)) & ESCerror)
{
ESC_ALerror (ALERR_INVALIDMBXCONFIG);
MBXrun = 0;
ESCvar.MBXrun = 0;
}
else
{
ESCvar.toggle = ESCvar.SM[1].ECrep; //sync repeat request toggle state
MBXrun = 1;
}
return state;
}
/** Check boostrap mailbox status by reading all SyncManager 0 and 1 data. The read values
* are compared with local definitions for SM Physical Address, SM Length and SM Control.
* If we check fails we disable Mailboxes by disabling SyncManager 0 and 1 and return
* state Init with Error flag set.
*
* @param[in] state = Current state request read from ALControl 0x0120
* @return if all Mailbox values is correct we return incoming state request, otherwise
* we return state Init with Error flag set.
*/
uint8_t ESC_checkmbxboot (uint8_t state)
{
_ESCsm2 *SM;
ESC_read (ESCREG_SM0, (void *) &ESCvar.SM[0], sizeof (ESCvar.SM[0]));
ESC_read (ESCREG_SM1, (void *) &ESCvar.SM[1], sizeof (ESCvar.SM[1]));
SM = (_ESCsm2 *) & ESCvar.SM[0];
if ((etohs (SM->PSA) != MBX0_sma_b) || (etohs (SM->Length) != MBX0_sml_b)
|| (SM->Command != MBX0_smc_b) || (ESCvar.SM[0].ECsm == 0))
{
ESCvar.SMtestresult = SMRESULT_ERRSM0;
ESC_SMdisable (0);
ESC_SMdisable (1);
return (uint8_t) (ESCinit | ESCerror); //fail state change
}
SM = (_ESCsm2 *) & ESCvar.SM[1];
if ((etohs (SM->PSA) != MBX1_sma_b) || (etohs (SM->Length) != MBX1_sml_b)
|| (SM->Command != MBX1_smc_b) || (ESCvar.SM[1].ECsm == 0))
{
ESCvar.SMtestresult = SMRESULT_ERRSM1;
ESC_SMdisable (0);
ESC_SMdisable (1);
return (uint8_t) (ESCinit | ESCerror); //fail state change
ESCvar.MBXrun = 1;
}
return state;
}
@ -259,19 +353,24 @@ uint8_t ESC_checkmbxboot (uint8_t state)
*/
uint8_t ESC_startmbxboot (uint8_t state)
{
/* Assign SM settings */
ESCvar.activembxsize = ESCvar.mbxsizeboot;
ESCvar.activemb0 = &ESCvar.mbboot[0];
ESCvar.activemb1 = &ESCvar.mbboot[1];
ESC_SMenable (0);
ESC_SMenable (1);
ESC_SMstatus (0);
ESC_SMstatus (1);
if ((state = ESC_checkmbxboot (state)) & ESCerror)
if ((state = ESC_checkmbx (state)) & ESCerror)
{
ESC_ALerror (ALERR_INVALIDBOOTMBXCONFIG);
MBXrun = 0;
ESCvar.MBXrun = 0;
}
else
{
ESCvar.toggle = ESCvar.SM[1].ECrep; //sync repeat request toggle state
MBXrun = 1;
ESCvar.MBXrun = 1;
}
return state;
}
@ -282,10 +381,10 @@ uint8_t ESC_startmbxboot (uint8_t state)
void ESC_stopmbx (void)
{
uint8_t n;
MBXrun = 0;
ESCvar.MBXrun = 0;
ESC_SMdisable (0);
ESC_SMdisable (1);
for (n = 0; n < MBXBUFFERS; n++)
for (n = 0; n < ESC_MBXBUFFERS; n++)
{
MBXcontrol[n].state = MBXstate_idle;
}
@ -307,39 +406,22 @@ void ESC_stopmbx (void)
*/
void ESC_readmbx (void)
{
_MBX *MB = &MBX[0];
_MBX *MB = (_MBX *)&MBX[0];
uint16_t length;
if (ESCvar.ALstatus == ESCboot)
{
ESC_read (MBX0_sma_b, MB, MBXHSIZE);
length = etohs (MB->header.length);
ESC_read (ESC_MBX0_sma, MB, ESC_MBXHSIZE);
length = etohs (MB->header.length);
if (length > (MBX0_sml_b - MBXHSIZE))
{
length = MBX0_sml_b - MBXHSIZE;
}
ESC_read (MBX0_sma_b + MBXHSIZE, &(MB->b[0]), length);
if (length + MBXHSIZE < MBX0_sml_b)
{
ESC_read (MBX0_sme_b, &length, 1);
}
}
else
if (length > (ESC_MBX0_sml - ESC_MBXHSIZE))
{
ESC_read (MBX0_sma, MB, MBXHSIZE);
length = etohs (MB->header.length);
if (length > (MBX0_sml - MBXHSIZE))
{
length = MBX0_sml - MBXHSIZE;
}
ESC_read (MBX0_sma + MBXHSIZE, &(MB->b[0]), length);
if (length + MBXHSIZE < MBX0_sml)
{
ESC_read (MBX0_sme, &length, 1);
}
length = ESC_MBX0_sml - ESC_MBXHSIZE;
}
ESC_read (ESC_MBX0_sma + ESC_MBXHSIZE, MB->b, length);
if (length + ESC_MBXHSIZE < ESC_MBX0_sml)
{
ESC_read (ESC_MBX0_sme, &length, 1);
}
MBXcontrol[0].state = MBXstate_inclaim;
}
/** Write local mailbox buffer ESCvar.MBX[n] to Send mailbox.
@ -350,34 +432,21 @@ void ESC_readmbx (void)
*/
void ESC_writembx (uint8_t n)
{
_MBX *MB = &MBX[n];
_MBXh *MBh = (_MBXh *)&MBX[n * ESC_MBXSIZE];
uint8_t dummy = 0;
uint16_t length;
length = etohs (MB->header.length);
if (ESCvar.ALstatus == ESCboot)
length = etohs (MBh->length);
if (length > (ESC_MBX1_sml - ESC_MBXHSIZE))
{
if (length > (MBX1_sml_b - MBXHSIZE))
{
length = MBX1_sml_b - MBXHSIZE;
}
ESC_write (MBX1_sma_b, MB, MBXHSIZE + length);
if (length + MBXHSIZE < MBX1_sml_b)
{
ESC_write (MBX1_sme_b, &dummy, 1);
}
length = ESC_MBX1_sml - ESC_MBXHSIZE;
}
else
ESC_write (ESC_MBX1_sma, MBh, ESC_MBXHSIZE + length);
if (length + ESC_MBXHSIZE < ESC_MBX1_sml)
{
if (length > (MBX1_sml - MBXHSIZE))
{
length = MBX1_sml - MBXHSIZE;
}
ESC_write (MBX1_sma, MB, MBXHSIZE + length);
if (length + MBXHSIZE < MBX1_sml)
{
ESC_write (MBX1_sme, &dummy, 1);
}
ESC_write (ESC_MBX1_sme, &dummy, 1);
}
ESCvar.mbxfree = 0;
}
@ -386,14 +455,8 @@ void ESC_writembx (uint8_t n)
void ESC_ackmbxread (void)
{
uint8_t dummy = 0;
if (ESCvar.ALstatus == ESCboot)
{
ESC_write (MBX1_sma_b, &dummy, 1);
}
else
{
ESC_write (MBX1_sma, &dummy, 1);
}
ESC_write (ESC_MBX1_sma, &dummy, 1);
ESCvar.mbxfree = 1;
}
@ -405,8 +468,8 @@ void ESC_ackmbxread (void)
*/
uint8_t ESC_claimbuffer (void)
{
_MBX *MB;
uint8_t n = MBXBUFFERS - 1;
_MBXh *MBh;
uint8_t n = ESC_MBXBUFFERS - 1;
while ((n > 0) && (MBXcontrol[n].state))
{
n--;
@ -414,16 +477,17 @@ uint8_t ESC_claimbuffer (void)
if (n)
{
MBXcontrol[n].state = MBXstate_outclaim;
MB = &MBX[n];
ESCvar.mbxcnt = (++ESCvar.mbxcnt) & 0x07;
MBh = (_MBXh *)&MBX[n * ESC_MBXSIZE];
ESCvar.mbxcnt++;
ESCvar.mbxcnt = (ESCvar.mbxcnt & 0x07);
if (ESCvar.mbxcnt == 0)
{
ESCvar.mbxcnt = 1;
}
MB->header.address = htoes (0x0000); // destination is master
MB->header.channel = 0;
MB->header.priority = 0;
MB->header.mbxcnt = ESCvar.mbxcnt;
MBh->address = htoes (0x0000); // destination is master
MBh->channel = 0;
MBh->priority = 0;
MBh->mbxcnt = ESCvar.mbxcnt;
ESCvar.txcue++;
}
return n;
@ -435,7 +499,7 @@ uint8_t ESC_claimbuffer (void)
*/
uint8_t ESC_outreqbuffer (void)
{
uint8_t n = MBXBUFFERS - 1;
uint8_t n = ESC_MBXBUFFERS - 1;
while ((n > 0) && (MBXcontrol[n].state != MBXstate_outreq))
{
n--;
@ -455,7 +519,7 @@ void MBX_error (uint16_t error)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
mbxerr = (_MBXerr *) & MBX[MBXout];
mbxerr = (_MBXerr *) &MBX[MBXout * ESC_MBXSIZE];
mbxerr->mbxheader.length = htoes ((uint16_t) 0x04);
mbxerr->mbxheader.mbxtype = MBXERR;
mbxerr->type = htoes ((uint16_t) 0x01);
@ -473,9 +537,9 @@ void MBX_error (uint16_t error)
uint8_t ESC_mbxprocess (void)
{
uint8_t mbxhandle = 0;
_MBX *MB = &MBX[0];
_MBXh *MBh = (_MBXh *)&MBX[0];
if (!MBXrun)
if (ESCvar.MBXrun == 0)
{
/* nothing to do */
return 0;
@ -520,7 +584,7 @@ uint8_t ESC_mbxprocess (void)
if (ESCvar.mbxoutpost || ESCvar.mbxbackup)
{
/* if outmbx empty */
if (!ESCvar.mbxoutpost)
if (ESCvar.mbxoutpost == 0)
{
/* use backup mbx */
ESC_writembx (ESCvar.mbxbackup);
@ -563,35 +627,26 @@ uint8_t ESC_mbxprocess (void)
}
/* read mailbox if full and no xoe in progress */
if (ESCvar.SM[0].MBXstat && !MBXcontrol[0].state && !ESCvar.mbxoutpost
&& !ESCvar.xoe)
if ((ESCvar.SM[0].MBXstat != 0) && (MBXcontrol[0].state == 0)
&& (ESCvar.mbxoutpost == 0) && (ESCvar.xoe == 0))
{
ESC_readmbx ();
ESCvar.SM[0].MBXstat = 0;
if (etohs (MB->header.length) == 0)
if (etohs (MBh->length) == 0)
{
MBX_error (MBXERR_INVALIDHEADER);
/* drop mailbox */
MBXcontrol[0].state = MBXstate_idle;
}
if ((MB->header.mbxcnt != 0) && (MB->header.mbxcnt == ESCvar.mbxincnt))
if ((MBh->mbxcnt != 0) && (MBh->mbxcnt == ESCvar.mbxincnt))
{
/* drop mailbox */
MBXcontrol[0].state = MBXstate_idle;
}
ESCvar.mbxincnt = MB->header.mbxcnt;
ESCvar.mbxincnt = MBh->mbxcnt;
return 1;
}
/* ack changes in non used SM */
if (ESCvar.ALevent & ESCREG_ALEVENT_SMCHANGE)
{
ESC_SMack (4);
ESC_SMack (5);
ESC_SMack (6);
ESC_SMack (7);
}
return 0;
}
/** Handler for incorrect or unsupported mailbox data. Write error response
@ -600,13 +655,13 @@ uint8_t ESC_mbxprocess (void)
void ESC_xoeprocess (void)
{
_MBXh *mbh;
if (!MBXrun)
if (ESCvar.MBXrun == 0)
{
return;
}
if (!ESCvar.xoe && (MBXcontrol[0].state == MBXstate_inclaim))
if ((ESCvar.xoe == 0) && (MBXcontrol[0].state == MBXstate_inclaim))
{
mbh = (_MBXh *) & MBX[0];
mbh = (_MBXh *) &MBX[0];
if ((mbh->mbxtype == 0) || (etohs (mbh->length) == 0))
{
MBX_error (MBXERR_INVALIDHEADER);
@ -630,18 +685,18 @@ uint8_t ESC_checkSM23 (uint8_t state)
{
_ESCsm2 *SM;
ESC_read (ESCREG_SM2, (void *) &ESCvar.SM[2], sizeof (ESCvar.SM[2]));
ESC_read (ESCREG_SM3, (void *) &ESCvar.SM[3], sizeof (ESCvar.SM[3]));
SM = (_ESCsm2 *) & ESCvar.SM[2];
if ((etohs (SM->PSA) != SM2_sma) || (etohs (SM->Length) != SM2_sml)
|| (SM->Command != SM2_smc) || !(SM->ActESC & SM2_act))
if ((etohs (SM->PSA) != ESC_SM2_sma) || (etohs (SM->Length) != ESCvar.ESC_SM2_sml)
|| (SM->Command != ESC_SM2_smc) || !(SM->ActESC & ESC_SM2_act))
{
ESCvar.SMtestresult = SMRESULT_ERRSM2;
/* fail state change */
return (ESCpreop | ESCerror);
}
ESC_read (ESCREG_SM3, (void *) &ESCvar.SM[3], sizeof (ESCvar.SM[3]));
SM = (_ESCsm2 *) & ESCvar.SM[3];
if ((etohs (SM->PSA) != SM3_sma) || (etohs (SM->Length) != SM3_sml)
|| (SM->Command != SM3_smc) || !(SM->ActESC & SM3_act))
if ((etohs (SM->PSA) != ESC_SM3_sma) || (etohs (SM->Length) != ESCvar.ESC_SM3_sml)
|| (SM->Command != ESC_SM3_smc) || !(SM->ActESC & ESC_SM3_act))
{
ESCvar.SMtestresult = SMRESULT_ERRSM3;
/* fail state change */
@ -659,11 +714,13 @@ uint8_t ESC_checkSM23 (uint8_t state)
*/
uint8_t ESC_startinput (uint8_t state)
{
state = ESC_checkSM23 (state);
if (state != (ESCpreop | ESCerror))
{
ESC_SMenable (3);
App.state = APPSTATE_INPUT;
CC_ATOMIC_SET(ESCvar.App.state, APPSTATE_INPUT);
}
else
{
@ -678,6 +735,43 @@ uint8_t ESC_startinput (uint8_t state)
ESC_ALerror (ALERR_INVALIDOUTPUTSM);
}
}
/* Exit here if polling */
if (ESCvar.use_interrupt == 0)
{
return state;
}
if (state != (ESCpreop | ESCerror))
{
uint16_t dc_check_result;
dc_check_result = ESC_checkDC();
if(dc_check_result > 0)
{
ESC_ALerror (dc_check_result);
state = (ESCpreop | ESCerror);
ESC_SMdisable (2);
ESC_SMdisable (3);
CC_ATOMIC_SET(ESCvar.App.state, APPSTATE_IDLE);
}
else
{
if (ESCvar.esc_hw_interrupt_enable != NULL)
{
if(ESCvar.dcsync > 0)
{
ESCvar.esc_hw_interrupt_enable(ESCREG_ALEVENT_DC_SYNC0 |
ESCREG_ALEVENT_SM2);
}
else
{
ESCvar.esc_hw_interrupt_enable(ESCREG_ALEVENT_SM2);
}
}
}
}
return state;
}
@ -687,9 +781,17 @@ uint8_t ESC_startinput (uint8_t state)
*/
void ESC_stopinput (void)
{
App.state = APPSTATE_IDLE;
CC_ATOMIC_SET(ESCvar.App.state, APPSTATE_IDLE);
ESC_SMdisable (3);
ESC_SMdisable (2);
/* Call interrupt disable hook case it have been configured */
if ((ESCvar.use_interrupt != 0) &&
(ESCvar.esc_hw_interrupt_disable != NULL))
{
ESCvar.esc_hw_interrupt_disable (ESCREG_ALEVENT_DC_SYNC0 |
ESCREG_ALEVENT_SM2);
}
}
@ -702,30 +804,121 @@ void ESC_stopinput (void)
*/
uint8_t ESC_startoutput (uint8_t state)
{
ESC_SMenable (2);
App.state |= APPSTATE_OUTPUT;
CC_ATOMIC_OR(ESCvar.App.state, APPSTATE_OUTPUT);
return state;
}
/** Unconditional stop of updating outputs by disabling Sync Manager 2.
* Set the App.state to APPSTATE_ONPUT. Call application hook APP_safeoutput
* Set the App.state to APPSTATE_INPUT. Call application hook APP_safeoutput
* letting the user to set safe state values on outputs.
*
*/
void ESC_stopoutput (void)
{
App.state &= APPSTATE_INPUT;
CC_ATOMIC_AND(ESCvar.App.state, APPSTATE_INPUT);
ESC_SMdisable (2);
APP_safeoutput ();
}
/** The state handler acting on ALControl Bit(0) and SyncManager Activation BIT(4)
/** The state handler acting on SyncManager Activation BIT(4)
* events in the Al Event Request register 0x220.
*
*/
void ESC_sm_act_event (void)
{
uint8_t ac, an, as, ax, ax23;
/* Have at least on Sync Manager changed */
if ((ESCvar.ALevent & ESCREG_ALEVENT_SMCHANGE) == 0)
{
/* nothing to do */
return;
}
/* Mask state request bits + Error ACK */
ac = ESCvar.ALcontrol & ESCREG_AL_STATEMASK;
as = ESCvar.ALstatus & ESCREG_AL_STATEMASK;
an = as;
if (((ac & ESCerror) || (ac == ESCinit)))
{
/* if error bit confirmed reset */
ac &= ESCREG_AL_ERRACKMASK;
an &= ESCREG_AL_ERRACKMASK;
}
/* Enter SM changed handling for all steps but Init and Boot when Mailboxes
* is up and running
*/
if ((as & ESCREG_AL_ALLBUTINITMASK) &&
((as == ESCboot) == 0) && ESCvar.MBXrun)
{
/* Validate Sync Managers, reading the Activation register will
* acknowledge the SyncManager Activation event making us enter
* this execution path.
*/
ax = ESC_checkmbx (as);
ax23 = ESC_checkSM23 (as);
if ((an & ESCerror) && ((ac & ESCerror) == 0))
{
/* if in error then stay there */
}
/* Have we been forced to step down to INIT we will stop mailboxes,
* update AL Status Code and exit ESC_state
*/
else if (ax == (ESCinit | ESCerror))
{
/* If we have activated Inputs and Outputs we need to disable them */
if (CC_ATOMIC_GET(ESCvar.App.state))
{
ESC_stopoutput ();
ESC_stopinput ();
}
/* Stop mailboxes and update ALStatus code */
ESC_stopmbx ();
ESC_ALerror (ALERR_INVALIDMBXCONFIG);
ESCvar.MBXrun = 0;
ESC_ALstatus (ax);
return;
}
/* Have we been forced to step down to PREOP we will stop inputs
* and outputs, update AL Status Code and exit ESC_state
*/
else if (CC_ATOMIC_GET(ESCvar.App.state) && (ax23 == (ESCpreop | ESCerror)))
{
ESC_stopoutput ();
ESC_stopinput ();
if (ESCvar.SMtestresult & SMRESULT_ERRSM3)
{
ESC_ALerror (ALERR_INVALIDINPUTSM);
}
else
{
ESC_ALerror (ALERR_INVALIDOUTPUTSM);
}
ESC_ALstatus (ax23);
}
}
else
{
ESC_SMack (0);
ESC_SMack (1);
ESC_SMack (2);
ESC_SMack (3);
ESC_SMack (4);
ESC_SMack (5);
ESC_SMack (6);
ESC_SMack (7);
}
}
/** The state handler acting on ALControl Bit(0)
* events in the Al Event Request register 0x220.
*
*/
void ESC_state (void)
{
uint8_t ac, an, as, ax, ax23;
uint8_t handle_smchanged = 0;
uint8_t ac, an, as;
/* Do we have a state change request pending */
if (ESCvar.ALevent & ESCREG_ALEVENT_CONTROL)
@ -734,11 +927,6 @@ void ESC_state (void)
sizeof (ESCvar.ALcontrol));
ESCvar.ALcontrol = etohs (ESCvar.ALcontrol);
}
/* Have at least on Sync Manager changed */
else if (ESCvar.ALevent & ESCREG_ALEVENT_SMCHANGE)
{
handle_smchanged = 1;
}
else
{
/* nothing to do */
@ -754,63 +942,9 @@ void ESC_state (void)
ac &= ESCREG_AL_ERRACKMASK;
an &= ESCREG_AL_ERRACKMASK;
}
/* Enter SM changed handling for all steps but Init and Boot when Mailboxes
* is up and running
*/
if (handle_smchanged && (as & ESCREG_AL_ALLBUTINITMASK) &&
!(as == ESCboot) && MBXrun)
{
/* Validate Sync Managers, reading the Activation register will
* acknowledge the SyncManager Activation event making us enter
* this execution path.
*/
ax = ESC_checkmbx (as);
ax23 = ESC_checkSM23 (as);
if ((an & ESCerror) && !(ac & ESCerror))
{
/* if in error then stay there */
return;
}
/* Have we been forced to step down to INIT we will stop mailboxes,
* update AL Status Code and exit ESC_state
*/
if (ax == (ESCinit | ESCerror))
{
/* If we have activated Inputs and Outputs we need to disable them */
if (App.state)
{
ESC_stopoutput ();
ESC_stopinput ();
}
/* Stop mailboxes and update ALStatus code */
ESC_stopmbx ();
ESC_ALerror (ALERR_INVALIDMBXCONFIG);
MBXrun = 0;
ESC_ALstatus (ax);
return;
}
/* Have we been forced to step down to PREOP we will stop inputs
* and outputs, update AL Status Code and exit ESC_state
*/
if ((App.state) && (ax23 == (ESCpreop | ESCerror)))
{
ESC_stopoutput ();
ESC_stopinput ();
if (ESCvar.SMtestresult & SMRESULT_ERRSM3)
{
ESC_ALerror (ALERR_INVALIDINPUTSM);
}
else
{
ESC_ALerror (ALERR_INVALIDOUTPUTSM);
}
ESC_ALstatus (ax23);
return;
}
}
/* Error state not acked, leave original */
if ((an & ESCerror) && !(ac & ESCerror))
if ((an & ESCerror) && ((ac & ESCerror) == 0))
{
return;
}
@ -819,9 +953,9 @@ void ESC_state (void)
as = (ac << 4) | (as & 0x0f);
/* Call post state change hook case it have been configured */
if ((esc_cfg != NULL) && esc_cfg->pre_state_change_hook)
if (ESCvar.pre_state_change_hook != NULL)
{
esc_cfg->pre_state_change_hook (&as, &an);
ESCvar.pre_state_change_hook (&as, &an);
}
/* Switch through the state change requested via AlControl from
@ -839,6 +973,7 @@ void ESC_state (void)
{
/* get station address */
ESC_address ();
COE_initDefaultSyncMgrPara ();
an = ESC_startmbx (ac);
break;
}
@ -860,10 +995,17 @@ void ESC_state (void)
case OP_TO_INIT:
{
ESC_stopoutput ();
ESC_stopinput ();
ESC_stopmbx ();
an = ESCinit;
break;
}
case SAFEOP_TO_INIT:
{
ESC_stopinput ();
ESC_stopmbx ();
an = ESCinit;
break;
}
case PREOP_TO_INIT:
{
@ -889,8 +1031,8 @@ void ESC_state (void)
case PREOP_TO_SAFEOP:
case SAFEOP_TO_SAFEOP:
{
SM2_sml = sizeRXPDO ();
SM3_sml = sizeTXPDO ();
ESCvar.ESC_SM2_sml = sizeOfPDO (RX_PDO_OBJIDX);
ESCvar.ESC_SM3_sml = sizeOfPDO (TX_PDO_OBJIDX);
an = ESC_startinput (ac);
if (an == ac)
{
@ -907,6 +1049,9 @@ void ESC_state (void)
case OP_TO_PREOP:
{
ESC_stopoutput ();
ESC_stopinput ();
an = ESCpreop;
break;
}
case SAFEOP_TO_PREOP:
{
@ -956,9 +1101,9 @@ void ESC_state (void)
}
/* Call post state change hook case it have been configured */
if ((esc_cfg != NULL) && esc_cfg->post_state_change_hook)
if (ESCvar.post_state_change_hook != NULL)
{
esc_cfg->post_state_change_hook (&as, &an);
ESCvar.post_state_change_hook (&as, &an);
}
if (!(an & ESCerror) && (ESCvar.ALerror))
@ -971,13 +1116,36 @@ void ESC_state (void)
}
/** Function copying the application configuration variable
* to the stack local pointer variable.
* data to the stack local variable.
*
* @param[in] cfg = Pointer to by the Application static declared
* configuration variable holding application specific details. Ex. post- and
* pre state change hooks
* @param[in] cfg = Pointer to the Application configuration variable
* holding application specific details. Data is copied.
*/
void ESC_config (esc_cfg_t * cfg)
{
esc_cfg = cfg;
/* Copy configuration data */
ESCvar.use_interrupt = cfg->use_interrupt;
ESCvar.watchdogcnt = cfg->watchdog_cnt;
ESCvar.mbxsize = cfg->mbxsize;
ESCvar.mbxsizeboot = cfg->mbxsizeboot;
ESCvar.mbxbuffers = cfg->mbxbuffers;
ESCvar.mb[0] = cfg->mb[0];
ESCvar.mb[1] = cfg->mb[1];
ESCvar.mbboot[0] = cfg->mb_boot[0];
ESCvar.mbboot[1] = cfg->mb_boot[1];
ESCvar.pdosm[0] = cfg->pdosm[0];
ESCvar.pdosm[1] = cfg->pdosm[1];
ESCvar.pre_state_change_hook = cfg->pre_state_change_hook;
ESCvar.post_state_change_hook = cfg->post_state_change_hook;
ESCvar.application_hook = cfg->application_hook;
ESCvar.safeoutput_override = cfg->safeoutput_override;
ESCvar.pre_object_download_hook = cfg->pre_object_download_hook;
ESCvar.post_object_download_hook = cfg->post_object_download_hook;
ESCvar.rxpdo_override = cfg->rxpdo_override;
ESCvar.txpdo_override = cfg->txpdo_override;
ESCvar.esc_hw_interrupt_enable = cfg->esc_hw_interrupt_enable;
ESCvar.esc_hw_interrupt_disable = cfg->esc_hw_interrupt_disable;
ESCvar.esc_hw_eep_handler = cfg->esc_hw_eep_handler;
}

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -36,31 +12,52 @@
#define __esc__
#include <cc.h>
#include "config.h"
#define ESCREG_ADDRESS 0x0010
#define ESCREG_DLSTATUS 0x0110
#define ESCREG_ALCONTROL 0x0120
#define ESCREG_ALSTATUS 0x0130
#define ESCREG_ALERROR 0x0134
#define ESCREG_ALEVENT 0x0220
#define ESCREG_ALEVENT_SM_MASK 0x0310
#define ESCREG_ALEVENT_SMCHANGE 0x0010
#define ESCREG_ALEVENT_CONTROL 0x0001
#define ESCREG_ALEVENT_SM2 0x0400
#define ESCREG_ALEVENT_SM3 0x0800
#define ESCREG_WDSTATUS 0x0440
#define ESCREG_SM0 0x0800
#define ESCREG_SM0STATUS (ESCREG_SM0 + 5)
#define ESCREG_SM0PDI (ESCREG_SM0 + 7)
#define ESCREG_SM1 (ESCREG_SM0 + 0x08)
#define ESCREG_SM2 (ESCREG_SM0 + 0x10)
#define ESCREG_SM3 (ESCREG_SM0 + 0x18)
#define ESCREG_LOCALTIME 0x0910
#define ESCREG_SMENABLE_BIT 0x01
#define ESCREG_AL_STATEMASK 0x001f
#define ESCREG_AL_ALLBUTINITMASK 0x0e
#define ESCREG_AL_ERRACKMASK 0x0f
#define ESCREG_ADDRESS 0x0010
#define ESCREG_DLSTATUS 0x0110
#define ESCREG_ALCONTROL 0x0120
#define ESCREG_ALSTATUS 0x0130
#define ESCREG_ALERROR 0x0134
#define ESCREG_ALEVENTMASK 0x0204
#define ESCREG_ALEVENT 0x0220
#define ESCREG_ALEVENT_SM_MASK 0x0310
#define ESCREG_ALEVENT_SMCHANGE 0x0010
#define ESCREG_ALEVENT_CONTROL 0x0001
#define ESCREG_ALEVENT_DC_LATCH 0x0002
#define ESCREG_ALEVENT_DC_SYNC0 0x0004
#define ESCREG_ALEVENT_DC_SYNC1 0x0008
#define ESCREG_ALEVENT_EEP 0x0020
#define ESCREG_ALEVENT_SM0 0x0100
#define ESCREG_ALEVENT_SM1 0x0200
#define ESCREG_ALEVENT_SM2 0x0400
#define ESCREG_ALEVENT_SM3 0x0800
#define ESCREG_WDSTATUS 0x0440
#define ESCREG_EECONTSTAT 0x0502
#define ESCREG_EEDATA 0x0508
#define ESCREG_SM0 0x0800
#define ESCREG_SM0STATUS (ESCREG_SM0 + 5)
#define ESCREG_SM0PDI (ESCREG_SM0 + 7)
#define ESCREG_SM1 (ESCREG_SM0 + 0x08)
#define ESCREG_SM2 (ESCREG_SM0 + 0x10)
#define ESCREG_SM3 (ESCREG_SM0 + 0x18)
#define ESCREG_LOCALTIME 0x0910
#define ESCREG_SYNC_ACT 0x0981
#define ESCREG_SYNC_ACT_ACTIVATED 0x01
#define ESCREG_SYNC_SYNC0_EN 0x02
#define ESCREG_SYNC_SYNC1_EN 0x04
#define ESCREG_SYNC_AUTO_ACTIVATED 0x08
#define ESCREG_SYNC0_CYCLE_TIME 0x09A0
#define ESCREG_SYNC1_CYCLE_TIME 0x09A4
#define ESCREG_SMENABLE_BIT 0x01
#define ESCREG_AL_STATEMASK 0x001f
#define ESCREG_AL_ALLBUTINITMASK 0x0e
#define ESCREG_AL_ERRACKMASK 0x0f
#define SYNCTYPE_SUPPORT_FREERUN 0x01
#define SYNCTYPE_SUPPORT_SYNCHRON 0x02
#define SYNCTYPE_SUPPORT_DCSYNC0 0x04
#define SYNCTYPE_SUPPORT_DCSYNC1 0x08
#define SYNCTYPE_SUPPORT_SUBCYCLE 0x10
#define ESCinit 0x01
#define ESCpreop 0x02
@ -99,12 +96,16 @@
#define ALERR_INVALIDSTATECHANGE 0x0011
#define ALERR_UNKNOWNSTATE 0x0012
#define ALERR_BOOTNOTSUPPORTED 0x0013
#define ALERR_NOVALIDFIRMWARE 0x0014
#define ALERR_INVALIDBOOTMBXCONFIG 0x0015
#define ALERR_INVALIDMBXCONFIG 0x0016
#define ALERR_INVALIDSMCONFIG 0x0017
#define ALERR_SYNCERROR 0x001A
#define ALERR_WATCHDOG 0x001B
#define ALERR_INVALIDOUTPUTSM 0x001D
#define ALERR_INVALIDINPUTSM 0x001E
#define ALERR_DCINVALIDSYNCCFG 0x0030
#define ALERR_DCSYNC0CYCLETIME 0x0036
#define MBXERR_SYNTAX 0x0001
#define MBXERR_UNSUPPORTEDPROTOCOL 0x0002
@ -164,9 +165,6 @@
#define COE_VALUEINFO_MAXIMUM 0x40
#define COE_MINIMUM_LENGTH 8
#define MBXHSIZE sizeof(_MBXh)
#define MBXDSIZE MBXSIZE-MBXHSIZE
#define MBXERR 0x00
#define MBXAOE 0x01
#define MBXEOE 0x02
@ -208,7 +206,50 @@
#define FOE_WAIT_FOR_FINAL_ACK 2
#define FOE_WAIT_FOR_DATA 3
#define APPSTATE_IDLE 0x00
#define APPSTATE_INPUT 0x01
#define APPSTATE_OUTPUT 0x02
typedef struct sm_cfg
{
uint16_t cfg_sma;
uint16_t cfg_sml;
uint16_t cfg_sme;
uint8_t cfg_smc;
uint8_t cfg_smact;
}sm_cfg_t;
typedef struct esc_cfg
{
void * user_arg;
int use_interrupt;
int watchdog_cnt;
size_t mbxsize;
size_t mbxsizeboot;
int mbxbuffers;
sm_cfg_t mb[2];
sm_cfg_t mb_boot[2];
sm_cfg_t pdosm[2];
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
void (*application_hook) (void);
void (*safeoutput_override) (void);
int (*pre_object_download_hook) (uint16_t index, uint8_t subindex);
void (*post_object_download_hook) (uint16_t index, uint8_t subindex);
void (*rxpdo_override) (void);
void (*txpdo_override) (void);
void (*esc_hw_interrupt_enable) (uint32_t mask);
void (*esc_hw_interrupt_disable) (uint32_t mask);
void (*esc_hw_eep_handler) (void);
} esc_cfg_t;
typedef struct
{
uint8_t state;
} _App;
// Attention! this struct is always little-endian
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t PSA;
@ -266,8 +307,10 @@ typedef struct CC_PACKED
uint8_t PDIsm:1;
#endif
} _ESCsm;
CC_PACKED_END
/* Attention! this struct is always little-endian */
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t PSA;
@ -277,17 +320,49 @@ typedef struct CC_PACKED
uint8_t ActESC;
uint8_t ActPDI;
} _ESCsm2;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t PSA;
uint16_t Length;
uint8_t Command;
} _ESCsmCompact;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t ALevent;
/* Configuration input is saved so the user variable may go out-of-scope */
int use_interrupt;
size_t mbxsize;
size_t mbxsizeboot;
int mbxbuffers;
sm_cfg_t mb[2];
sm_cfg_t mbboot[2];
sm_cfg_t pdosm[2];
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
void (*application_hook) (void);
void (*safeoutput_override) (void);
int (*pre_object_download_hook) (uint16_t index, uint8_t subindex);
void (*post_object_download_hook) (uint16_t index, uint8_t subindex);
void (*rxpdo_override) (void);
void (*txpdo_override) (void);
void (*esc_hw_interrupt_enable) (uint32_t mask);
void (*esc_hw_interrupt_disable) (uint32_t mask);
void (*esc_hw_eep_handler) (void);
uint8_t MBXrun;
size_t activembxsize;
sm_cfg_t * activemb0;
sm_cfg_t * activemb1;
uint16_t ESC_SM2_sml;
uint16_t ESC_SM3_sml;
uint16_t TXPDOsize;
uint16_t RXPDOsize;
uint8_t dcsync;
uint16_t synccounterlimit;
uint16_t ALstatus;
uint16_t ALcontrol;
uint16_t ALerror;
@ -320,12 +395,18 @@ typedef struct CC_PACKED
uint8_t SMtestresult;
int16_t temp;
uint16_t wdcnt;
uint32_t PrevTime;
uint32_t Time;
_ESCsm SM[4];
/* Volatile since it may be read from ISR */
volatile int watchdogcnt;
volatile uint32_t Time;
volatile uint16_t ALevent;
volatile int8_t synccounter;
volatile _App App;
} _ESCvar;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t length;
@ -347,18 +428,24 @@ typedef struct CC_PACKED
uint8_t mbxtype:4;
#endif
} _MBXh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh header;
uint8_t b[MBXDSIZE];
uint8_t b[0];
} _MBX;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t numberservice;
} _COEh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
#if defined(EC_LITTLE_ENDIAN)
@ -374,14 +461,18 @@ typedef struct CC_PACKED
uint8_t reserved;
uint16_t fragmentsleft;
} _INFOh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
uint16_t type;
uint16_t detail;
} _MBXerr;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
@ -391,7 +482,9 @@ typedef struct CC_PACKED
uint8_t subindex;
uint32_t size;
} _COEsdo;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
@ -403,7 +496,9 @@ typedef struct CC_PACKED
uint8_t objectcode;
char name;
} _COEobjdesc;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
@ -417,7 +512,9 @@ typedef struct CC_PACKED
uint16_t access;
char name;
} _COEentdesc;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint8_t opcode;
@ -429,22 +526,21 @@ typedef struct CC_PACKED
uint32_t errorcode;
};
} _FOEh;
CC_PACKED_END
#define FOEHSIZE (sizeof(_FOEh))
#define FOE_DATA_SIZE (MBXSIZEBOOT - (MBXHSIZE+FOEHSIZE))
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
_FOEh foeheader;
union
{
char filename[FOE_DATA_SIZE];
uint8_t data[FOE_DATA_SIZE];
char errortext[FOE_DATA_SIZE];
char filename[0];
uint8_t data[0];
char errortext[0];
};
} _FOE;
CC_PACKED_END
/* state definition in mailbox
* 0 : idle
* 1 : claimed for inbox
@ -459,14 +555,35 @@ typedef struct
uint8_t state;
} _MBXcontrol;
typedef struct esc_cfg
{
void (*pre_state_change_hook) (uint8_t * as, uint8_t * an);
void (*post_state_change_hook) (uint8_t * as, uint8_t * an);
} esc_cfg_t;
/* Stack reference to application configuration of the ESC */
#define ESC_MBXSIZE (ESCvar.activembxsize)
#define ESC_MBX0_sma (ESCvar.activemb0->cfg_sma)
#define ESC_MBX0_sml (ESCvar.activemb0->cfg_sml)
#define ESC_MBX0_sme (ESCvar.activemb0->cfg_sme)
#define ESC_MBX0_smc (ESCvar.activemb0->cfg_smc)
#define ESC_MBX1_sma (ESCvar.activemb1->cfg_sma)
#define ESC_MBX1_sml (ESCvar.activemb1->cfg_sml)
#define ESC_MBX1_sme (ESCvar.activemb1->cfg_sme)
#define ESC_MBX1_smc (ESCvar.activemb1->cfg_smc)
#define ESC_MBXBUFFERS (ESCvar.mbxbuffers)
#define ESC_SM2_sma (ESCvar.pdosm[0].cfg_sma)
#define ESC_SM2_smc (ESCvar.pdosm[0].cfg_smc)
#define ESC_SM2_act (ESCvar.pdosm[0].cfg_smact)
#define ESC_SM3_sma (ESCvar.pdosm[1].cfg_sma)
#define ESC_SM3_smc (ESCvar.pdosm[1].cfg_smc)
#define ESC_SM3_act (ESCvar.pdosm[1].cfg_smact)
#define ESC_MBXHSIZE sizeof(_MBXh)
#define ESC_MBXDSIZE (ESC_MBXSIZE - ESC_MBXHSIZE)
#define ESC_FOEHSIZE sizeof(_FOEh)
#define ESC_FOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_FOEHSIZE))
void ESC_config (esc_cfg_t * cfg);
void ESC_ALerror (uint16_t errornumber);
void ESC_ALeventwrite (uint32_t event);
uint32_t ESC_ALeventread (void);
void ESC_ALeventmaskwrite (uint32_t mask);
uint32_t ESC_ALeventmaskread (void);
void ESC_ALstatus (uint8_t status);
void ESC_SMstatus (uint8_t n);
uint8_t ESC_WDstatus (void);
@ -481,31 +598,44 @@ void ESC_stopinput (void);
uint8_t ESC_startoutput (uint8_t state);
void ESC_stopoutput (void);
void ESC_state (void);
void ESC_sm_act_event (void);
/* From hardware file */
void ESC_read (uint16_t address, void *buf, uint16_t len);
void ESC_write (uint16_t address, void *buf, uint16_t len);
void ESC_init (const void * arg);
void ESC_init (const esc_cfg_t * cfg);
void ESC_reset (void);
/* From application */
extern void APP_safeoutput ();
extern _ESCvar ESCvar;
extern _MBXcontrol MBXcontrol[];
extern uint8_t MBX[];
extern volatile _ESCvar ESCvar;
extern _MBX MBX[MBXBUFFERS];
extern _MBXcontrol MBXcontrol[MBXBUFFERS];
extern uint8_t MBXrun;
extern uint16_t SM2_sml, SM3_sml;
/* ATOMIC operations are used when running interrupt driven */
#ifndef CC_ATOMIC_SET
#define CC_ATOMIC_SET(var,val) (var = val)
#endif
typedef struct
{
uint8_t state;
} _App;
#ifndef CC_ATOMIC_GET
#define CC_ATOMIC_GET(var) (var)
#endif
#define APPSTATE_IDLE 0x00
#define APPSTATE_INPUT 0x01
#define APPSTATE_OUTPUT 0x02
#ifndef CC_ATOMIC_ADD
#define CC_ATOMIC_ADD(var,val) (var += val)
#endif
#ifndef CC_ATOMIC_SUB
#define CC_ATOMIC_SUB(var,val) (var -= val)
#endif
#ifndef CC_ATOMIC_AND
#define CC_ATOMIC_AND(var,val) (var &= val)
#endif
#ifndef CC_ATOMIC_OR
#define CC_ATOMIC_OR(var,val) (var |= val)
#endif
extern _App App;
#endif

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -41,121 +18,6 @@
#define BITS2BYTES(b) ((b + 7) >> 3)
extern uint8_t txpdoitems;
extern uint8_t rxpdoitems;
/** Search for an object index matching the wanted value in the Object List.
*
* @param[in] index = value on index of object we want to locate
* @return local array index if we succeed, -1 if we didn't find the index.
*/
int32_t SDO_findobject (uint16_t index)
{
int32_t n = 0;
while (SDOobjects[n].index < index)
{
n++;
}
if (SDOobjects[n].index != index)
{
return -1;
}
return n;
}
/** Calculate the size in Bytes of TxPDOs by adding the objects in SyncManager
* SDO 1C13.
*
* @return size of TxPDOs in Bytes.
*/
uint16_t sizeTXPDO (void)
{
uint16_t size = 0, hobj, l, si, c, sic;
int16_t nidx;
const _objd *objd;
if (SDO1C13[0].data)
{
si = *((uint8_t *) SDO1C13[0].data);
}
else
{
si = (uint8_t) SDO1C13[0].value;
}
if (si)
{
for (sic = 1; sic <= si; sic++)
{
if (SDO1C13[sic].data)
{
hobj = *((uint16_t *) SDO1C13[sic].data);
hobj = htoes(hobj);
}
else
{
hobj = (uint16_t) SDO1C13[sic].value;
}
nidx = SDO_findobject (hobj);
if (nidx > 0)
{
objd = SDOobjects[nidx].objdesc;
l = (uint8_t) objd->value;
for (c = 1; c <= l; c++)
{
size += ((objd + c)->value & 0xff);
}
}
}
}
return BITS2BYTES (size);
}
/** Calculate the size in Bytes of RxPDOs by adding the objects in SyncManager
* SDO 1C12.
*
* @return size of RxPDOs in Bytes.
*/
uint16_t sizeRXPDO (void)
{
uint16_t size = 0, hobj, c, l, si, sic;
int16_t nidx;
const _objd *objd;
if (SDO1C12[0].data)
{
si = *((uint8_t *) SDO1C12[0].data);
}
else
{
si = (uint8_t) SDO1C12[0].value;
}if (si)
{
for (sic = 1; sic <= si; sic++)
{
if (SDO1C12[sic].data)
{
hobj = *((uint16_t *) SDO1C12[sic].data);
hobj = htoes(hobj);
}
else
{
hobj = (uint16_t) SDO1C12[sic].value;
}
nidx = SDO_findobject (hobj);
if (nidx > 0)
{
objd = SDOobjects[nidx].objdesc;
l = (uint8_t) objd->value;
for (c = 1; c <= l; c++)
{
size += ((objd + c)->value & 0xff);
}
}
}
}
return BITS2BYTES (size);
}
/** Search for an object sub-index.
*
* @param[in] nidx = local array index of object we want to find sub-index to
@ -180,6 +42,203 @@ int16_t SDO_findsubindex (int16_t nidx, uint8_t subindex)
return n;
}
/** Search for an object index matching the wanted value in the Object List.
*
* @param[in] index = value on index of object we want to locate
* @return local array index if we succeed, -1 if we didn't find the index.
*/
int32_t SDO_findobject (uint16_t index)
{
int32_t n = 0;
while (SDOobjects[n].index < index)
{
n++;
}
if (SDOobjects[n].index != index)
{
return -1;
}
return n;
}
/** Get the value for requested SDO 0x1C32 or 0x1C33 sub index
*
* @param[in] index = value on index of object we want to locate
* @param[in] subindex = value on subindex of object we want to locate
* @param[out] buf = buf to copy value to
* @param[in] datatype = EtherCAT datatype of buf
* @return 1 if value was found, else 0.
*/
int COE_getSyncMgrPara (uint16_t index, uint8_t subindex, void * buf, uint16_t datatype)
{
int result = 0;
int32_t nidx;
int32_t snidx;
const _objd *objd;
nidx = SDO_findobject(index);
if(nidx < 0)
{
return result;
}
else if((index != 0x1c32) && (index != 0x1c33) && (index != 0x10F1))
{
return result;
}
snidx = SDO_findsubindex(nidx, subindex);
if(snidx >= 0)
{
objd = SDOobjects[nidx].objdesc;
if((objd[snidx].data != NULL) &&
(objd[snidx].datatype == datatype))
{
memcpy(buf, objd[snidx].data, objd[snidx].bitlength / 8 );
result = 1;
}
else
{
if((datatype == DTYPE_UNSIGNED32) &&
(objd[snidx].datatype == datatype))
{
*(uint32_t *)buf = objd[snidx].value;
result = 1;
}
else if((datatype == DTYPE_UNSIGNED16) &&
(objd[snidx].datatype == datatype))
{
*(uint16_t *)buf = (uint16_t)objd[snidx].value;
result = 1;
}
else if((datatype == DTYPE_UNSIGNED8) &&
(objd[snidx].datatype == datatype))
{
*(uint8_t *)buf = (uint8_t)objd[snidx].value;
result = 1;
}
}
}
return result;
}
/** Init default values for SDO Sync Objects
*
*/
void COE_initDefaultSyncMgrPara (void)
{
uint32_t i,j;
const _objd *objd;
int32_t n = 0;
/* 1C3x */
for(i = 0x1C32; i <= 0x1C33; i ++)
{
/* Look if index is present */
n = SDO_findobject(i);
if(n < 0)
{
continue;
}
/* Load default values */
objd = SDOobjects[n].objdesc;
for(j = 1; j <= SDOobjects[n].maxsub; j++ )
{
if(objd[j].data != NULL)
{
*(uint32_t *)objd[j].data = objd[j].value;
}
if(objd[j].subindex >= SDOobjects[n].maxsub)
{
break;
}
}
}
/* Look if index is present */
n = SDO_findobject(0x10F1);
if(n >= 0)
{
/* Load default values */
objd = SDOobjects[n].objdesc;
for(j = 1; j <= objd[0].value; j++ )
{
if(objd[j].data != NULL)
{
*(uint32_t *)objd[j].data = objd[j].value;
}
}
}
}
/** Calculate the size in Bytes of RxPDO or TxPDOs by adding the objects
* in SyncManager
* SDO 1C1x.
*
* @return size of RxPDO or TxPDOs in Bytes.
*/
uint16_t sizeOfPDO (uint16_t index)
{
uint16_t size = 0, hobj, l, si, c, sic;
int16_t nidx;
const _objd *objd;
const _objd *objd1c1x;
nidx = SDO_findobject (index);
if(nidx < 0)
{
return size;
}
else if((index != RX_PDO_OBJIDX) && (index != TX_PDO_OBJIDX))
{
return size;
}
objd1c1x = objd = SDOobjects[nidx].objdesc;
if (objd1c1x[0].data)
{
si = *((uint8_t *) objd1c1x[0].data);
}
else
{
si = (uint8_t) objd1c1x[0].value;
}
if (si)
{
for (sic = 1; sic <= si; sic++)
{
if (objd1c1x[sic].data)
{
hobj = *((uint16_t *) objd1c1x[sic].data);
hobj = htoes(hobj);
}
else
{
hobj = (uint16_t) objd1c1x[sic].value;
}
nidx = SDO_findobject (hobj);
if (nidx > 0)
{
objd = SDOobjects[nidx].objdesc;
l = (uint8_t) objd->value;
for (c = 1; c <= l; c++)
{
size += ((objd + c)->value & 0xff);
}
}
}
}
return BITS2BYTES (size);
}
/** Copy to mailbox.
*
* @param[in] source = pointer to source
@ -204,7 +263,7 @@ void SDO_abort (uint16_t index, uint8_t subindex, uint32_t abortcode)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coeres = (_COEsdo *) &MBX[MBXout];
coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
coeres->mbxheader.length = htoes (COE_DEFAULTLENGTH);
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
@ -244,7 +303,7 @@ void SDO_upload (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coeres = (_COEsdo *) &MBX[MBXout];
coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
coeres->mbxheader.length = htoes (COE_DEFAULTLENGTH);
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
@ -292,13 +351,13 @@ void SDO_upload (void)
/* convert bits to bytes */
size = (size + 7) >> 3;
coeres->size = htoel (size);
if ((size + COE_HEADERSIZE) > MBXDSIZE)
if ((size + COE_HEADERSIZE) > ESC_MBXDSIZE)
{
/* segmented transfer needed */
/* set total size in bytes */
ESCvar.frags = size;
/* limit to mailbox size */
size = MBXDSIZE - COE_HEADERSIZE;
size = ESC_MBXDSIZE - COE_HEADERSIZE;
/* number of bytes done */
ESCvar.fragsleft = size;
/* signal segmented transfer */
@ -342,18 +401,18 @@ void SDO_uploadsegment (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coeres = (_COEsdo *) &MBX[MBXout];
coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
offset = ESCvar.fragsleft;
size = ESCvar.frags - ESCvar.fragsleft;
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDORESPONSE << 12));
coeres->command = COE_COMMAND_UPLOADSEGMENT + (coesdo->command & COE_TOGGLEBIT); // copy toggle bit
if ((size + COE_SEGMENTHEADERSIZE) > MBXDSIZE)
if ((size + COE_SEGMENTHEADERSIZE) > ESC_MBXDSIZE)
{
/* more segmented transfer needed */
/* limit to mailbox size */
size = MBXDSIZE - COE_SEGMENTHEADERSIZE;
size = ESC_MBXDSIZE - COE_SEGMENTHEADERSIZE;
/* number of bytes done */
ESCvar.fragsleft += size;
coeres->mbxheader.length = htoes (COE_SEGMENTHEADERSIZE + size);
@ -383,26 +442,6 @@ void SDO_uploadsegment (void)
ESCvar.xoe = 0;
}
/** 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)
{
if ((index == 0x1c12) && (subindex > 0) && (rxpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
if ((index == 0x1c13) && (subindex > 0) && (txpdoitems != 0))
{
SDO_abort (index, subindex, ABORT_READONLY);
return 0;
}
return 1;
}
/** Function for handling incoming requested SDO Download, validating the
* request and sending an response. On error an SDO Abort will be sent.
@ -452,7 +491,7 @@ void SDO_download (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coeres = (_COEsdo *) &MBX[MBXout];
coeres = (_COEsdo *) &MBX[MBXout * ESC_MBXSIZE];
coeres->mbxheader.length = htoes (COE_DEFAULTLENGTH);
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
@ -508,7 +547,7 @@ void SDO_infoerror (uint32_t abortcode)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coeres = (_COEobjdesc *) &MBX[MBXout];
coeres = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coeres->mbxheader.length = htoes ((uint16_t) 0x0a);
coeres->mbxheader.mbxtype = MBXCOE;
coeres->coeheader.numberservice =
@ -520,10 +559,12 @@ void SDO_infoerror (uint32_t abortcode)
coeres->infoheader.fragmentsleft = 0;
coeres->index = htoel (abortcode);
MBXcontrol[MBXout].state = MBXstate_outreq;
MBXcontrol[0].state = MBXstate_idle;
ESCvar.xoe = 0;
}
}
#define ODLISTSIZE ((MBX1_sml - MBXHSIZE - sizeof(_COEh) - sizeof(_INFOh) - 2) & 0xfffe)
#define ODLISTSIZE ((ESC_MBX1_sml - ESC_MBXHSIZE - sizeof(_COEh) - sizeof(_INFOh) - 2) & 0xfffe)
/** Function for handling incoming requested SDO Get OD List, validating the
* request and sending an response. On error an SDO Info Error will be sent.
@ -556,7 +597,7 @@ void SDO_getodlist (void)
}
if (MBXout)
{
coel = (_COEobjdesc *) &MBX[MBXout];
coel = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
@ -632,7 +673,7 @@ void SDO_getodlistcont (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coel = (_COEobjdesc *) &MBX[MBXout];
coel = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
@ -686,7 +727,7 @@ void SDO_getod (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coel = (_COEobjdesc *) &MBX[MBXout];
coel = (_COEobjdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
@ -709,7 +750,7 @@ void SDO_getod (void)
coel->objectcode = SDOobjects[nidx].objtype;
s = (uint8_t *) SDOobjects[nidx].name;
d = (uint8_t *) &(coel->name);
while (*s && (n < (MBXDSIZE - 0x0c)))
while (*s && (n < (ESC_MBXDSIZE - 0x0c)))
{
*d = *s;
n++;
@ -757,7 +798,7 @@ void SDO_geted (void)
MBXout = ESC_claimbuffer ();
if (MBXout)
{
coel = (_COEentdesc *) &MBX[MBXout];
coel = (_COEentdesc *) &MBX[MBXout * ESC_MBXSIZE];
coel->mbxheader.mbxtype = MBXCOE;
coel->coeheader.numberservice =
htoes ((0 & 0x01f) | (COE_SDOINFORMATION << 12));
@ -774,7 +815,7 @@ void SDO_geted (void)
coel->access = htoes ((objd + nsub)->access);
s = (uint8_t *) (objd + nsub)->name;
d = (uint8_t *) &(coel->name);
while (*s && (n < (MBXDSIZE - 0x10)))
while (*s && (n < (ESC_MBXDSIZE - 0x10)))
{
*d = *s;
n++;
@ -809,7 +850,7 @@ void ESC_coeprocess (void)
_COEsdo *coesdo;
_COEobjdesc *coeobjdesc;
uint8_t service;
if (!MBXrun)
if (ESCvar.MBXrun == 0)
{
return;
}

View File

@ -1,29 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2013 Arthur Ketels
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -36,6 +13,7 @@
#include <cc.h>
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t subindex;
@ -46,7 +24,9 @@ typedef struct CC_PACKED
uint32_t value;
void *data;
} _objd;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t index;
@ -56,6 +36,7 @@ typedef struct CC_PACKED
const char *name;
const _objd *objdesc;
} _objectlist;
CC_PACKED_END
#define OBJH_READ 0
#define OBJH_WRITE 1
@ -100,14 +81,17 @@ typedef struct CC_PACKED
#define ATYPE_RXPDO 0x40
#define ATYPE_TXPDO 0x80
#define TX_PDO_OBJIDX 0x1c13
#define RX_PDO_OBJIDX 0x1c12
void ESC_coeprocess (void);
uint16_t sizeTXPDO (void);
uint16_t sizeRXPDO (void);
uint16_t sizeOfPDO (uint16_t index);
void SDO_abort (uint16_t index, uint8_t subindex, uint32_t abortcode);
void COE_initDefaultSyncMgrPara (void);
int COE_getSyncMgrPara (uint16_t index, uint8_t subindex, void * buf, uint16_t datatype);
extern void ESC_objecthandler (uint16_t index, uint8_t subindex);
extern int ESC_pre_objecthandler (uint16_t index, uint8_t subindex);
extern const _objectlist SDOobjects[];
extern const _objd SDO1C12[];
extern const _objd SDO1C13[];
#endif

View File

@ -1,31 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2010 ZBE Inc.
* Copyright (C) 2011-2013 Arthur Ketels.
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,31 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2010 ZBE Inc.
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -36,22 +11,18 @@
#ifndef __esc_eep__
#define __esc_eep__
#include "cc.h"
/* EEPROM emulation related ESC registers */
#define ESCREG_EECONTSTAT 0x0502
#define ESCREG_EEDATA 0x0508
#define ESCREG_ALEVENT_EEP 0x0020
#include <cc.h>
#include "esc.h"
/* EEPROM commands */
#define EEP_CMD_IDLE 0x0
#define EEP_CMD_READ 0x1
#define EEP_CMD_WRITE 0x2
#define EEP_CMD_RELOAD 0x3
#define EEP_CMD_IDLE 0x0
#define EEP_CMD_READ 0x1
#define EEP_CMD_WRITE 0x2
#define EEP_CMD_RELOAD 0x3
/* read/write size */
#define EEP_READ_SIZE 8
#define EEP_WRITE_SIZE 2
#define EEP_READ_SIZE 8
#define EEP_WRITE_SIZE 2
/* CONSTAT register content */
typedef struct CC_PACKED
@ -77,6 +48,24 @@ typedef struct CC_PACKED
uint32_t addr;
} eep_stat_t;
/**
* ECAT EEPROM configuration area data structure
*/
typedef union eep_config
{
struct
{
uint16_t pdi_control;
uint16_t pdi_configuration;
uint16_t sync_impulse_len;
uint16_t pdi_configuration2;
uint16_t configured_station_alias;
uint8_t reserved[4];
uint16_t checksum;
};
uint32_t dword[4]; /**< Four 32 bit double word equivalent to 8 16 bit configuration area word. */
}eep_config_t;
/* periodic task */
void EEP_process (void);

View File

@ -1,31 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2010 ZBE Inc.
* Copyright (C) 2011-2013 Arthur Ketels.
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -103,6 +78,7 @@ int FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
{
foe_file = &foe_files[i];
foe_file->address_offset = 0;
foe_file->total_size = 0;
switch (op)
{
case FOE_OP_RRQ:
@ -182,6 +158,8 @@ uint16_t FOE_fwrite (uint8_t *data, uint16_t length)
ncopied++;
}
foe_file->total_size += ncopied;
DPRINT("FOE_fwrite END with : %d\n",ncopied);
return ncopied;
}
@ -242,8 +220,8 @@ void FOE_abort (uint32_t code)
mbxhandle = ESC_claimbuffer ();
if (mbxhandle)
{
foembx = (_FOE *) & MBX[mbxhandle];
foembx->mbxheader.length = htoes (FOEHSIZE); /* Don't bother with error text for now. */
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
foembx->mbxheader.length = htoes (ESC_FOEHSIZE); /* Don't bother with error text for now. */
foembx->mbxheader.mbxtype = MBXFOE;
foembx->foeheader.opcode = FOE_OP_ERR;
foembx->foeheader.errorcode = htoel (code);
@ -275,7 +253,7 @@ int FOE_send_data_packet ()
mbxhandle = ESC_claimbuffer ();
if (mbxhandle)
{
foembx = (_FOE *) & MBX[mbxhandle];
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
data_len = FOE_fread (foembx->data, FOE_DATA_SIZE);
foembx->foeheader.opcode = FOE_OP_DATA;
foembx->foeheader.packetnumber = htoel (FOEvar.foepacket);
@ -306,8 +284,8 @@ int FOE_send_ack ()
if (mbxhandle)
{
DPRINT("FOE_send_ack\n");
foembx = (_FOE *) & MBX[mbxhandle];
foembx->mbxheader.length = htoes (FOEHSIZE);
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
foembx->mbxheader.length = htoes (ESC_FOEHSIZE);
foembx->mbxheader.mbxtype = MBXFOE;
foembx->foeheader.opcode = FOE_OP_ACK;
foembx->foeheader.packetnumber = htoel (FOEvar.foepacket);
@ -429,7 +407,7 @@ void FOE_write ()
FOE_init ();
foembx = (_FOE *) &MBX[0];
data_len = etohs (foembx->mbxheader.length) - FOEHSIZE;
data_len = etohs (foembx->mbxheader.length) - ESC_FOEHSIZE;
password = etohl (foembx->foeheader.password);
/* Get an address we can write the file to, if possible. */
@ -470,7 +448,7 @@ void FOE_data ()
}
foembx = (_FOE*)&MBX[0];
data_len = etohs(foembx->mbxheader.length) - FOEHSIZE;
data_len = etohs(foembx->mbxheader.length) - ESC_FOEHSIZE;
packet = etohl(foembx->foeheader.packetnumber);
if (packet != FOEvar.foepacket)
@ -498,7 +476,7 @@ void FOE_data ()
DPRINT("FOE_data no copied\n");
FOE_abort (FOE_ERR_PROGERROR);
}
else if (data_len == FOE_DATA_SIZE)
else if (data_len == ESC_FOE_DATA_SIZE)
{
DPRINT("FOE_data data_len == FOE_DATA_SIZE\n");
if (ncopied != data_len)
@ -585,7 +563,7 @@ void ESC_foeprocess (void)
_MBXh *mbh;
_FOE *foembx;
if (!MBXrun)
if (ESCvar.MBXrun == 0)
{
return;
}
@ -601,7 +579,7 @@ void ESC_foeprocess (void)
{
foembx = (_FOE *) &MBX[0];
/* Verify the size of the file data. */
if (etohs (foembx->mbxheader.length) < FOEHSIZE)
if (etohs (foembx->mbxheader.length) < ESC_FOEHSIZE)
{
FOE_abort (MBXERR_SIZETOOSHORT);
}

View File

@ -1,31 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2010 ZBE Inc.
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -52,9 +27,11 @@ struct foe_writefile_cfg
uint32_t dest_start_address;
/** Current address during write of file */
uint32_t address_offset;
/* FoE password */
/** Calculated size of file received */
uint32_t total_size;
/** FoE password */
uint32_t filepass;
/* Pointer to application foe write function */
/** Pointer to application foe write function */
uint32_t (*write_function) (foe_writefile_cfg_t * self, uint8_t * data);
};

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2017 Arthur Ketels
* Copyright (C) 2012-2017 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -34,7 +10,6 @@
* Function to read and write commands to the ESC. Used to read/write ESC
* registers and memory.
*/
#include "utypes.h"
#include "esc.h"
#include <string.h>
#include <fcntl.h>
@ -450,10 +425,10 @@ void ESC_reset (void)
}
void ESC_init (const void * arg)
void ESC_init (const esc_cfg_t * config)
{
uint32_t value;
const char * spi_name = (char *)arg;
const char * spi_name = (char *)config->user_arg;
lan9252 = open (spi_name, O_RDWR, 0);
/* Reset the ecat core here due to evb-lan9252-digio not having any GPIO

View File

@ -1,30 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* Copyright (C) 2007-2017 Arthur Ketels
* Copyright (C) 2012-2017 rt-labs.
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -35,7 +11,6 @@
* registers and memory.
*/
#include "utypes.h"
#include "esc.h"
#include <spi/spi.h>
#include <string.h>
@ -414,10 +389,10 @@ void ESC_reset (void)
}
void ESC_init (const void * arg)
void ESC_init (const esc_cfg_t * config)
{
uint32_t value;
const char * spi_name = (char *)arg;
const char * spi_name = (char *)config->user_arg;
lan9252 = open (spi_name, O_RDWR, 0);
/* Reset the ecat core here due to evb-lan9252-digio not having any GPIO

View File

@ -1,33 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* File : esc_hw.c
* Version : 0.9.2
* Date : 22-02-2010
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
@ -38,7 +11,6 @@
* registers and memory.
*/
#include "utypes.h"
#include "../../esc.h"
#include <spi/spi.h>
#include <string.h>
@ -146,9 +118,9 @@ void ESC_reset (void)
DPRINT("esc_reset_ended\n");
}
void ESC_init (const void * arg)
void ESC_init (const esc_cfg_t * config)
{
const char * spi_name = (char *)arg;
const char * spi_name = (char *)config->user_arg;
et1100 = open (spi_name, O_RDWR, 0);
read_termination[sizeof(read_termination) - 1] = 0xFF;
}

View File

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

View File

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

View File

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

View File

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

View File

@ -1,33 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* File : esc_hw.c
* Version : 0.9.2
* Date : 22-02-2010
* Copyright (C) 2007-2013 Arthur Ketels
* Copyright (C) 2012-2013 rt-labs
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,32 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* File : esc_hw_eep.c
* Version : 1.0.0
* Date : 26-08-2016
* Copyright (C) 2016 Sascha Ittner
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,32 +1,6 @@
/*
* SOES Simple Open EtherCAT Slave
*
* File : esc_hw_eep.h
* Version : 1.0.0
* Date : 26-08-2016
* Copyright (C) 2016 Sascha Ittner
*
* SOES is free software; you can redistribute it and/or modify it under
* the terms of the GNU General Public License version 2 as published by the Free
* Software Foundation.
*
* SOES is distributed in the hope that it will be useful, but WITHOUT ANY
* WARRANTY; without even the implied warranty of MERCHANTABILITY or
* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* As a special exception, if other files instantiate templates or use macros
* or inline functions from this file, or you compile this file and link it
* with other works to produce a work based on this file, this file does not
* by itself cause the resulting work to be covered by the GNU General Public
* License. However the source code for this file must still be made available
* in accordance with section (3) of the GNU General Public License.
*
* This exception does not invalidate any other reasons why a work based on
* this file might be covered by the GNU General Public License.
*
* The EtherCAT Technology, the trade name and logo "EtherCAT" are the intellectual
* property of, and protected by Beckhoff Automation GmbH.
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file

View File

@ -1,3 +1,8 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#ifndef CC_H
#define CC_H
@ -8,6 +13,8 @@ extern "C"
#include <assert.h>
#include <stdint.h>
#include <stddef.h>
#include <sys/param.h>
#ifdef __linux__
#include <endian.h>
#else
@ -24,6 +31,13 @@ extern "C"
#define CC_SWAP32(x) __builtin_bswap32 (x)
#define CC_SWAP16(x) ((uint16_t)(x) >> 8 | ((uint16_t)(x) & 0xFF) << 8)
#define CC_ATOMIC_SET(var,val) __atomic_store_n(&var,val,__ATOMIC_SEQ_CST)
#define CC_ATOMIC_GET(var) __atomic_load_n(&var,__ATOMIC_SEQ_CST)
#define CC_ATOMIC_ADD(var,val) __atomic_add_fetch(&var,val,__ATOMIC_SEQ_CST)
#define CC_ATOMIC_SUB(var,val) __atomic_sub_fetch(&var,val,__ATOMIC_SEQ_CST)
#define CC_ATOMIC_AND(var,val) __atomic_and_fetch(&var,val,__ATOMIC_SEQ_CST)
#define CC_ATOMIC_OR(var,val) __atomic_or_fetch(&var,val,__ATOMIC_SEQ_CST)
#if BYTE_ORDER == BIG_ENDIAN
#define htoes(x) CC_SWAP16 (x)
#define htoel(x) CC_SWAP32 (x)