Ny structure. Start of the "main" branch

This commit is contained in:
Hakan Bastedt
2024-11-20 11:18:13 +01:00
parent 31b896871d
commit 1918604586
415 changed files with 202039 additions and 21080 deletions

View File

@@ -0,0 +1,29 @@
# NOTE: add headers to make them show up in an IDE
add_library (soes
esc.c
esc.h
esc_coe.c
esc_coe.h
esc_foe.c
esc_foe.h
esc_eoe.c
esc_eoe.h
esc_eep.c
esc_eep.h
ecat_slv.c
ecat_slv.h
options.h
${HAL_SOURCES}
)
include_directories(${HAL_INCLUDES})
install (TARGETS soes DESTINATION bin)
install (FILES
esc.h
esc_coe.h
esc_foe.h
esc_eoe.h
esc_eep.h
DESTINATION include)

View File

@@ -0,0 +1,388 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#include <stddef.h>
#include "esc.h"
#include "esc_coe.h"
#include "esc_foe.h"
#include "esc_eoe.h"
#include "ecat_slv.h"
#define IS_RXPDO(index) ((index) >= 0x1600 && (index) < 0x1800)
#define IS_TXPDO(index) ((index) >= 0x1A00 && (index) < 0x1C00)
/* Global variables used by the stack */
uint8_t MBX[MBXBUFFERS * MAX(MBXSIZE,MBXSIZEBOOT)];
_MBXcontrol MBXcontrol[MBXBUFFERS];
_SMmap SMmap2[MAX_MAPPINGS_SM2];
_SMmap SMmap3[MAX_MAPPINGS_SM3];
_ESCvar ESCvar;
/* Private variables */
static volatile int watchdog;
#if MAX_MAPPINGS_SM2 > 0
static uint8_t rxpdo[MAX_RXPDO_SIZE] __attribute__((aligned (8)));
#else
extern uint8_t rxpdo[];
#endif
#if MAX_MAPPINGS_SM3 > 0
static uint8_t txpdo[MAX_TXPDO_SIZE] __attribute__((aligned (8)));
#else
extern uint8_t txpdo[];
#endif
/** 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 SDO abort code, or 0 on success
*/
uint32_t ESC_download_pre_objecthandler (uint16_t index,
uint8_t subindex,
void * data,
size_t size,
uint16_t flags)
{
if (IS_RXPDO (index) ||
IS_TXPDO (index) ||
index == RX_PDO_OBJIDX ||
index == TX_PDO_OBJIDX)
{
uint8_t minSub = ((flags & COMPLETE_ACCESS_FLAG) == 0) ? 0 : 1;
if (subindex > minSub && COE_maxSub (index) != 0)
{
return ABORT_SUBINDEX0_NOT_ZERO;
}
}
if (ESCvar.pre_object_download_hook)
{
return (ESCvar.pre_object_download_hook) (index,
subindex,
data,
size,
flags);
}
return 0;
}
/** 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
* @return SDO abort code, or 0 on success
*/
uint32_t ESC_download_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags)
{
if (ESCvar.post_object_download_hook != NULL)
{
return (ESCvar.post_object_download_hook)(index, subindex, flags);
}
return 0;
}
/** Function to pre-qualify the incoming SDO upload.
*
* @param[in] index = index of SDO upload request to handle
* @param[in] sub-index = sub-index of SDO upload request to handle
* @return SDO abort code, or 0 on success
*/
uint32_t ESC_upload_pre_objecthandler (uint16_t index,
uint8_t subindex,
void * data,
size_t *size,
uint16_t flags)
{
if (ESCvar.pre_object_upload_hook != NULL)
{
return (ESCvar.pre_object_upload_hook) (index,
subindex,
data,
size,
flags);
}
return 0;
}
/** Hook called from the slave stack SDO Upload handler to act on
* user specified Index and Sub-index.
*
* @param[in] index = index of SDO upload request to handle
* @param[in] sub-index = sub-index of SDO upload request to handle
* @return SDO abort code, or 0 on success
*/
uint32_t ESC_upload_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags)
{
if (ESCvar.post_object_upload_hook != NULL)
{
return (ESCvar.post_object_upload_hook)(index, subindex, flags);
}
return 0;
}
/** 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.
*/
void APP_safeoutput (void)
{
DPRINT ("APP_safeoutput\n");
if(ESCvar.safeoutput_override != NULL)
{
(ESCvar.safeoutput_override)();
}
}
/** Write local process data to Sync Manager 3, Master Inputs.
*/
void TXPDO_update (void)
{
if(ESCvar.txpdo_override != NULL)
{
(ESCvar.txpdo_override)();
}
else
{
if (MAX_MAPPINGS_SM3 > 0)
{
COE_pdoPack (txpdo, ESCvar.sm3mappings, SMmap3);
}
ESC_write (ESC_SM3_sma, txpdo, ESCvar.ESC_SM3_sml);
}
}
/** 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 (ESC_SM2_sma, rxpdo, ESCvar.ESC_SM2_sml);
if (MAX_MAPPINGS_SM2 > 0)
{
COE_pdoUnpack (rxpdo, ESCvar.sm2mappings, SMmap2);
}
}
}
/* Set the watchdog count value, don't have any affect when using
* HW watchdog 0x4xx
*
* @param[in] watchdogcnt = new watchdog count value
*/
void APP_setwatchdog (int watchdogcnt)
{
CC_ATOMIC_SET(ESCvar.watchdogcnt, watchdogcnt);
}
/* 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) &&
(ESCvar.ESC_SM2_sml > 0))
{
DPRINT("DIG_process watchdog expired\n");
ESC_ALstatusgotoerror((ESCsafeop | ESCerror), ALERR_WATCHDOG);
}
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);
/* Set outputs */
cb_set_outputs();
}
else if (ESCvar.ALevent & ESCREG_ALEVENT_SM2)
{
ESC_read (ESC_SM2_sma, rxpdo, ESCvar.ESC_SM2_sml);
}
}
/* Call application */
if ((flags & DIG_PROCESS_APP_HOOK_FLAG) > 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_inputs();
TXPDO_update();
}
}
}
/*
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
* control what interrupts that should be served and re-activated with
* event mask argument
*/
void ecat_slv_worker (uint32_t event_mask)
{
do
{
/* Check the state machine */
ESC_state();
/* Check the SM activation event */
ESC_sm_act_event();
/* Check mailboxes */
while ((ESC_mbxprocess() > 0) || (ESCvar.txcue > 0))
{
ESC_coeprocess();
#if USE_FOE
ESC_foeprocess();
#endif
#if USE_EOE
ESC_eoeprocess();
#endif
ESC_xoeprocess();
}
#if USE_EOE
ESC_eoeprocess_tx();
#endif
/* Call emulated eeprom handler if set */
if (ESCvar.esc_hw_eep_handler != NULL)
{
(ESCvar.esc_hw_eep_handler)();
}
CC_ATOMIC_SET(ESCvar.ALevent, ESC_ALeventread());
}while(ESCvar.ALevent & event_mask);
ESC_ALeventmaskwrite(ESC_ALeventmaskread() | event_mask);
}
/*
* 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();
#if USE_FOE
ESC_foeprocess();
#endif
#if USE_EOE
ESC_eoeprocess();
#endif
ESC_xoeprocess();
}
#if USE_EOE
ESC_eoeprocess_tx();
#endif
/* Call emulated eeprom handler if set */
if (ESCvar.esc_hw_eep_handler != NULL)
{
(ESCvar.esc_hw_eep_handler)();
}
}
/*
* Poll all events in a free-run application
*/
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");
/* 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);
}
#if USE_FOE
/* Init FoE */
FOE_init ();
#endif
#if USE_EOE
/* Init EoE */
EOE_init ();
#endif
/* reset ESC to init state */
ESC_ALstatus (ESCinit);
ESC_ALerror (ALERR_NONE);
ESC_stopmbx ();
ESC_stopinput ();
ESC_stopoutput ();
/* Init Object Dictionary default values */
COE_initDefaultValues ();
}

View File

@@ -0,0 +1,69 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#ifndef __ECAT_SLV_H__
#define __ECAT_SLV_H__
#include "options.h"
#include "esc.h"
/**
* This function is called when to get input values
*/
void cb_get_inputs();
/**
* This function is called when to set outputs values
*/
void cb_set_outputs();
/** Set the watchdog count value
*
* @param[in] watchdogcnt = new watchdog count value
*/
void APP_setwatchdog (int watchdogcnt);
#define DIG_PROCESS_INPUTS_FLAG 0x01
#define DIG_PROCESS_OUTPUTS_FLAG 0x02
#define DIG_PROCESS_WD_FLAG 0x04
#define DIG_PROCESS_APP_HOOK_FLAG 0x08
/** Implements the watch-dog counter to count if we should make a state change
* due to missing incoming SM2 events. Updates local I/O and run the application
* in the following order, call read EtherCAT outputs, execute user provided
* application hook and call write EtherCAT inputs.
*
* @param[in] flags = User input what to execute
*/
void DIG_process (uint8_t flags);
/**
* Handler for SM change, SM0/1, AL CONTROL and EEPROM events, the application
* control what interrupts that should be served and re-activated with
* event mask argument
*
* @param[in] event_mask = Event mask for interrupts to serve and re-activate
* after served
*/
void ecat_slv_worker (uint32_t event_mask);
/**
* 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 /* __ECAT_SLV_H__ */

View File

@@ -0,0 +1,783 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for esc.h
*/
#ifndef __esc__
#define __esc__
#include <stdbool.h>
#include <cc.h>
#include <esc_coe.h>
#include "options.h"
#define ESCREG_ADDRESS 0x0010
#define ESCREG_CONF_STATION_ALIAS 0x0012
#define ESCREG_DLSTATUS 0x0110
#define ESCREG_ALCONTROL 0x0120
#define ESCREG_ALCONTROL_ERROR_ACK 0x0010
#define ESCREG_ALSTATUS 0x0130
#define ESCREG_ALSTATUS_ERROR_IND 0x0010
#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_WD 0x0040
#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_SM0ACTIVATE (ESCREG_SM0 + 6)
#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_LOCALTIME_OFFSET 0x0920
#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 ESCREG_AL_ID_REQUEST 0x0020
#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
#define ESCboot 0x03
#define ESCsafeop 0x04
#define ESCop 0x08
#define ESCerror 0x10
#define INIT_TO_INIT 0x11
#define INIT_TO_PREOP 0x21
#define INIT_TO_BOOT 0x31
#define INIT_TO_SAFEOP 0x41
#define INIT_TO_OP 0x81
#define PREOP_TO_INIT 0x12
#define PREOP_TO_PREOP 0x22
#define PREOP_TO_BOOT 0x32
#define PREOP_TO_SAFEOP 0x42
#define PREOP_TO_OP 0x82
#define BOOT_TO_INIT 0x13
#define BOOT_TO_PREOP 0x23
#define BOOT_TO_BOOT 0x33
#define BOOT_TO_SAFEOP 0x43
#define BOOT_TO_OP 0x83
#define SAFEOP_TO_INIT 0x14
#define SAFEOP_TO_PREOP 0x24
#define SAFEOP_TO_BOOT 0x34
#define SAFEOP_TO_SAFEOP 0x44
#define SAFEOP_TO_OP 0x84
#define OP_TO_INIT 0x18
#define OP_TO_PREOP 0x28
#define OP_TO_BOOT 0x38
#define OP_TO_SAFEOP 0x48
#define OP_TO_OP 0x88
#define ALERR_NONE 0x0000
#define ALERR_UNSPECIFIEDERROR 0x0001
#define ALERR_NOMEMORY 0x0002
#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_NOVALIDINPUTS 0x0018
#define ALERR_NOVALIDOUTPUTS 0x0019
#define ALERR_SYNCERROR 0x001A
#define ALERR_WATCHDOG 0x001B
#define ALERR_INVALIDSYNCMANAGERTYP 0x001C
#define ALERR_INVALIDOUTPUTSM 0x001D
#define ALERR_INVALIDINPUTSM 0x001E
#define ALERR_INVALIDWDTCFG 0x001F
#define ALERR_SLAVENEEDSCOLDSTART 0x0020
#define ALERR_SLAVENEEDSINIT 0x0021
#define ALERR_SLAVENEEDSPREOP 0x0022
#define ALERR_SLAVENEEDSSAFEOP 0x0023
#define ALERR_INVALIDINPUTMAPPING 0x0024
#define ALERR_INVALIDOUTPUTMAPPING 0x0025
#define ALERR_INCONSISTENTSETTINGS 0x0026
#define ALERR_FREERUNNOTSUPPORTED 0x0027
#define ALERR_SYNCNOTSUPPORTED 0x0028
#define ALERR_FREERUNNEEDS3BUFFMODE 0x0029
#define ALERR_BACKGROUNDWATCHDOG 0x002A
#define ALERR_NOVALIDINPUTSOUTPUTS 0x002B
#define ALERR_FATALSYNCERROR 0x002C
#define ALERR_NOSYNCERROR 0x002D
#define ALERR_INVALIDINPUTFMMUCFG 0x002E
#define ALERR_DCINVALIDSYNCCFG 0x0030
#define ALERR_INVALIDDCLATCHCFG 0x0031
#define ALERR_PLLERROR 0x0032
#define ALERR_DCSYNCIOERROR 0x0033
#define ALERR_DCSYNCTIMEOUT 0x0034
#define ALERR_DCSYNCCYCLETIME 0x0035
#define ALERR_DCSYNC0CYCLETIME 0x0036
#define ALERR_DCSYNC1CYCLETIME 0x0037
#define ALERR_MBXAOE 0x0041
#define ALERR_MBXEOE 0x0042
#define ALERR_MBXCOE 0x0043
#define ALERR_MBXFOE 0x0044
#define ALERR_MBXSOE 0x0045
#define ALERR_MBXVOE 0x004F
#define ALERR_EEPROMNOACCESS 0x0050
#define ALERR_EEPROMERROR 0x0051
#define ALERR_SLAVERESTARTEDLOCALLY 0x0060
#define ALERR_DEVICEIDVALUEUPDATED 0x0061
#define ALERR_APPLCTRLAVAILABLE 0x00f0
#define ALERR_UNKNOWN 0xffff
#define MBXERR_SYNTAX 0x0001
#define MBXERR_UNSUPPORTEDPROTOCOL 0x0002
#define MBXERR_INVALIDCHANNEL 0x0003
#define MBXERR_SERVICENOTSUPPORTED 0x0004
#define MBXERR_INVALIDHEADER 0x0005
#define MBXERR_SIZETOOSHORT 0x0006
#define MBXERR_NOMOREMEMORY 0x0007
#define MBXERR_INVALIDSIZE 0x0008
#define ABORT_NOTOGGLE 0x05030000
#define ABORT_TRANSFER_TIMEOUT 0x05040000
#define ABORT_UNKNOWN 0x05040001
#define ABORT_INVALID_BLOCK_SIZE 0x05040002
#define ABORT_INVALID_SEQUENCE_NUMBER 0x05040003
#define ABORT_BLOCK_CRC_ERROR 0x05040004
#define ABORT_OUT_OF_MEMORY 0x05040005
#define ABORT_UNSUPPORTED 0x06010000
#define ABORT_WRITEONLY 0x06010001
#define ABORT_READONLY 0x06010002
#define ABORT_SUBINDEX0_NOT_ZERO 0x06010003
#define ABORT_CA_NOT_SUPPORTED 0x06010004
#define ABORT_EXCEEDS_MBOX_SIZE 0x06010005
#define ABORT_SDO_DOWNLOAD_BLOCKED 0x06010006
#define ABORT_NOOBJECT 0x06020000
#define ABORT_MAPPING_OBJECT_ERROR 0x06040041
#define ABORT_MAPPING_LENGTH_ERROR 0x06040042
#define ABORT_GENERAL_PARAMETER_ERROR 0x06040043
#define ABORT_GENERAL_DEVICE_ERROR 0x06040047
#define ABORT_HARDWARE_ERROR 0x06060000
#define ABORT_TYPEMISMATCH 0x06070010
#define ABORT_DATATYPE_TOO_HIGH 0x06070012
#define ABORT_DATATYPE_TOO_LOW 0x06070013
#define ABORT_NOSUBINDEX 0x06090011
#define ABORT_VALUE_EXCEEDED 0x06090030
#define ABORT_VALUE_TOO_HIGH 0x06090031
#define ABORT_VALUE_TOO_LOW 0x06090032
#define ABORT_MODULE_LIST_MISMATCH 0x06090033
#define ABORT_MAX_VAL_LESS_THAN_MIN_VAL 0x06090036
#define ABORT_RESOURCE_NOT_AVAILABLE 0x060A0023
#define ABORT_GENERALERROR 0x08000000
#define ABORT_DATA_STORE_ERROR 0x08000020
#define ABORT_DATA_STORE_LOCAL_ERROR 0x08000021
#define ABORT_NOTINTHISSTATE 0x08000022
#define ABORT_OBJECT_DICTIONARY_ERROR 0x08000023
#define ABORT_NO_DATA_AVAILABLE 0x08000024
#define MBXstate_idle 0x00
#define MBXstate_inclaim 0x01
#define MBXstate_outclaim 0x02
#define MBXstate_outreq 0x03
#define MBXstate_outpost 0x04
#define MBXstate_backup 0x05
#define MBXstate_again 0x06
#define COE_DEFAULTLENGTH 0x0AU
#define COE_HEADERSIZE 0x0AU
#define COE_SEGMENTHEADERSIZE 0x03U
#define COE_SDOREQUEST 0x02
#define COE_SDORESPONSE 0x03
#define COE_SDOINFORMATION 0x08
#define COE_COMMAND_SDOABORT 0x80
#define COE_COMMAND_UPLOADREQUEST 0x40
#define COE_COMMAND_UPLOADRESPONSE 0x40
#define COE_COMMAND_UPLOADSEGMENT 0x00
#define COE_COMMAND_UPLOADSEGREQ 0x60
#define COE_COMMAND_DOWNLOADREQUEST 0x20
#define COE_COMMAND_DOWNLOADRESPONSE 0x60
#define COE_COMMAND_DOWNLOADSEGREQ 0x00
#define COE_COMMAND_DOWNLOADSEGRESP 0x20
#define COE_COMMAND_LASTSEGMENTBIT 0x01
#define COE_SIZE_INDICATOR 0x01
#define COE_EXPEDITED_INDICATOR 0x02
#define COE_COMPLETEACCESS 0x10
#define COE_TOGGLEBIT 0x10
#define COE_INFOERROR 0x07
#define COE_GETODLISTRESPONSE 0x02
#define COE_GETODRESPONSE 0x04
#define COE_ENTRYDESCRIPTIONRESPONSE 0x06
#define COE_VALUEINFO_ACCESS 0x01
#define COE_VALUEINFO_OBJECT 0x02
#define COE_VALUEINFO_MAPPABLE 0x04
#define COE_VALUEINFO_TYPE 0x08
#define COE_VALUEINFO_DEFAULT 0x10
#define COE_VALUEINFO_MINIMUM 0x20
#define COE_VALUEINFO_MAXIMUM 0x40
#define COE_MINIMUM_LENGTH 8
#define MBXERR 0x00
#define MBXAOE 0x01
#define MBXEOE 0x02
#define MBXCOE 0x03
#define MBXFOE 0x04
#define MBXODL 0x10
#define MBXOD 0x20
#define MBXED 0x30
#define MBXSEU 0x40
#define MBXSED 0x50
#define SMRESULT_ERRSM0 0x01
#define SMRESULT_ERRSM1 0x02
#define SMRESULT_ERRSM2 0x04
#define SMRESULT_ERRSM3 0x08
#define FOE_ERR_NOTDEFINED 0x8000
#define FOE_ERR_NOTFOUND 0x8001
#define FOE_ERR_ACCESS 0x8002
#define FOE_ERR_DISKFULL 0x8003
#define FOE_ERR_ILLEGAL 0x8004
#define FOE_ERR_PACKETNO 0x8005
#define FOE_ERR_EXISTS 0x8006
#define FOE_ERR_NOUSER 0x8007
#define FOE_ERR_BOOTSTRAPONLY 0x8008
#define FOE_ERR_NOTINBOOTSTRAP 0x8009
#define FOE_ERR_NORIGHTS 0x800A
#define FOE_ERR_PROGERROR 0x800B
#define FOE_ERR_CHECKSUM 0x800C
#define FOE_OP_RRQ 1
#define FOE_OP_WRQ 2
#define FOE_OP_DATA 3
#define FOE_OP_ACK 4
#define FOE_OP_ERR 5
#define FOE_OP_BUSY 6
#define FOE_READY 0
#define FOE_WAIT_FOR_ACK 1
#define FOE_WAIT_FOR_FINAL_ACK 2
#define FOE_WAIT_FOR_DATA 3
#define EOE_RESULT_SUCCESS 0x0000
#define EOE_RESULT_UNSPECIFIED_ERROR 0x0001
#define EOE_RESULT_UNSUPPORTED_FRAME_TYPE 0x0002
#define EOE_RESULT_NO_IP_SUPPORT 0x0201
#define EOE_RESULT_NO_DHCP_SUPPORT 0x0202
#define EOE_RESULT_NO_FILTER_SUPPORT 0x0401
#define APPSTATE_IDLE 0x00
#define APPSTATE_INPUT 0x01
#define APPSTATE_OUTPUT 0x02
#define PREALLOC_BUFFER_SIZE (PREALLOC_FACTOR * MBXSIZE)
#ifdef __cplusplus
extern "C" {
#endif
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;
bool skip_default_initialization;
void (*set_defaults_hook) (void);
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);
uint32_t (*pre_object_download_hook) (uint16_t index,
uint8_t subindex,
void * data,
size_t size,
uint16_t flags);
uint32_t (*post_object_download_hook) (uint16_t index,
uint8_t subindex,
uint16_t flags);
uint32_t (*pre_object_upload_hook) (uint16_t index,
uint8_t subindex,
void * data,
size_t *size,
uint16_t flags);
uint32_t (*post_object_upload_hook) (uint16_t index,
uint8_t subindex,
uint16_t flags);
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);
uint16_t (*esc_check_dc_handler) (void);
int (*get_device_id) (uint16_t * device_id);
} 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;
uint16_t Length;
#if defined(EC_LITTLE_ENDIAN)
uint8_t Mode:2;
uint8_t Direction:2;
uint8_t IntECAT:1;
uint8_t IntPDI:1;
uint8_t WTE:1;
uint8_t R1:1;
uint8_t IntW:1;
uint8_t IntR:1;
uint8_t R2:1;
uint8_t MBXstat:1;
uint8_t BUFstat:2;
uint8_t R3:2;
uint8_t ECsm:1;
uint8_t ECrep:1;
uint8_t ECr4:4;
uint8_t EClatchEC:1;
uint8_t EClatchPDI:1;
uint8_t PDIsm:1;
uint8_t PDIrep:1;
uint8_t PDIr5:6;
#endif
#if defined(EC_BIG_ENDIAN)
uint8_t R1:1;
uint8_t WTE:1;
uint8_t IntPDI:1;
uint8_t IntECAT:1;
uint8_t Direction:2;
uint8_t Mode:2;
uint8_t R3:2;
uint8_t BUFstat:2;
uint8_t MBXstat:1;
uint8_t R2:1;
uint8_t IntR:1;
uint8_t IntW:1;
uint8_t EClatchPDI:1;
uint8_t EClatchEC:1;
uint8_t ECr4:4;
uint8_t ECrep:1;
uint8_t ECsm:1;
uint8_t PDIr5:6;
uint8_t PDIrep:1;
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;
uint16_t Length;
uint8_t Command;
uint8_t Status;
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
typedef struct
{
/* Configuration input is saved so the user variable may go out-of-scope */
int use_interrupt;
sm_cfg_t mb[2];
sm_cfg_t mbboot[2];
bool skip_default_initialization;
void (*set_defaults_hook) (void);
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);
uint32_t (*pre_object_download_hook) (uint16_t index,
uint8_t subindex,
void * data,
size_t size,
uint16_t flags);
uint32_t (*post_object_download_hook) (uint16_t index,
uint8_t subindex,
uint16_t flags);
uint32_t (*pre_object_upload_hook) (uint16_t index,
uint8_t subindex,
void * data,
size_t *size,
uint16_t flags);
uint32_t (*post_object_upload_hook) (uint16_t index,
uint8_t subindex,
uint16_t flags);
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);
uint16_t (*esc_check_dc_handler) (void);
int (*get_device_id) (uint16_t * device_id);
uint8_t MBXrun;
uint32_t activembxsize;
sm_cfg_t * activemb0;
sm_cfg_t * activemb1;
uint16_t ESC_SM2_sml;
uint16_t ESC_SM3_sml;
uint8_t dcsync;
uint16_t synccounterlimit;
uint16_t ALstatus;
uint16_t ALcontrol;
uint16_t ALerror;
uint16_t DLstatus;
uint16_t address;
uint8_t mbxcnt;
uint8_t mbxincnt;
uint8_t mbxoutpost;
uint8_t mbxbackup;
uint8_t xoe;
uint8_t txcue;
uint8_t mbxfree;
uint8_t segmented;
void *data;
uint16_t entries;
uint32_t frags;
uint32_t fragsleft;
uint16_t index;
uint8_t subindex;
uint16_t flags;
uint8_t toggle;
int sm2mappings;
int sm3mappings;
uint8_t SMtestresult;
uint32_t PrevTime;
_ESCsm SM[4];
/* Volatile since it may be read from ISR */
volatile int watchdogcnt;
volatile uint32_t Time;
volatile uint32_t ALevent;
volatile int8_t synccounter;
volatile _App App;
uint8_t mbxdata[PREALLOC_BUFFER_SIZE];
} _ESCvar;
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t length;
uint16_t address;
#if defined(EC_LITTLE_ENDIAN)
uint8_t channel:6;
uint8_t priority:2;
uint8_t mbxtype:4;
uint8_t mbxcnt:4;
#endif
#if defined(EC_BIG_ENDIAN)
uint8_t priority:2;
uint8_t channel:6;
uint8_t mbxcnt:4;
uint8_t mbxtype:4;
#endif
} _MBXh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh header;
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)
uint8_t opcode:7;
uint8_t incomplete:1;
#endif
#if defined(EC_BIG_ENDIAN)
uint8_t incomplete:1;
uint8_t opcode:7;
#endif
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 CC_ALIGNED(4)
{
_MBXh mbxheader;
_COEh coeheader;
uint8_t command;
uint16_t index;
uint8_t subindex;
uint32_t size;
} _COEsdo;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED CC_ALIGNED(4)
{
_MBXh mbxheader;
_COEh coeheader;
_INFOh infoheader;
uint16_t index;
uint16_t datatype;
uint8_t maxsub;
uint8_t objectcode;
char name;
} _COEobjdesc;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
_COEh coeheader;
_INFOh infoheader;
uint16_t index;
uint8_t subindex;
uint8_t valueinfo;
uint16_t datatype;
uint16_t bitlength;
uint16_t access;
char name;
} _COEentdesc;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint8_t opcode;
uint8_t reserved;
union
{
uint32_t password;
uint32_t packetnumber;
uint32_t errorcode;
};
} _FOEh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
_FOEh foeheader;
union
{
char filename[0];
uint8_t data[0];
char errortext[0];
};
} _FOE;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
uint16_t frameinfo1;
union
{
uint16_t frameinfo2;
uint16_t result;
};
} _EOEh;
CC_PACKED_END
CC_PACKED_BEGIN
typedef struct CC_PACKED
{
_MBXh mbxheader;
_EOEh eoeheader;
uint8_t data[0];
} _EOE;
CC_PACKED_END
/* state definition in mailbox
* 0 : idle
* 1 : claimed for inbox
* 2 : claimed for outbox
* 3 : request post outbox
* 4 : outbox posted not send
* 5 : backup outbox
* 6 : mailbox needs to be transmitted again
*/
typedef struct
{
uint8_t state;
} _MBXcontrol;
/* 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 (MBXBUFFERS)
#define ESC_SM2_sma (SM2_sma)
#define ESC_SM2_smc (SM2_smc)
#define ESC_SM2_act (SM2_act)
#define ESC_SM3_sma (SM3_sma)
#define ESC_SM3_smc (SM3_smc)
#define ESC_SM3_act (SM3_act)
#define ESC_MBXHSIZE ((uint32_t)sizeof(_MBXh))
#define ESC_MBXDSIZE (ESC_MBXSIZE - ESC_MBXHSIZE)
#define ESC_FOEHSIZE (uint32_t)sizeof(_FOEh)
#define ESC_FOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_FOEHSIZE))
#define ESC_EOEHSIZE ((uint32_t)sizeof(_EOEh))
#define ESC_EOE_DATA_SIZE (ESC_MBXSIZE - (ESC_MBXHSIZE +ESC_EOEHSIZE))
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_ALstatusgotoerror (uint8_t status, uint16_t errornumber);
void ESC_SMstatus (uint8_t n);
uint8_t ESC_WDstatus (void);
uint8_t ESC_claimbuffer (void);
uint8_t ESC_startmbx (uint8_t state);
void ESC_stopmbx (void);
void MBX_error (uint16_t error);
uint8_t ESC_mbxprocess (void);
void ESC_xoeprocess (void);
uint8_t ESC_startinput (uint8_t state);
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 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 _SMmap SMmap2[];
extern _SMmap SMmap3[];
#ifdef __cplusplus
}
#endif
/* ATOMIC operations are used when running interrupt driven */
#ifndef CC_ATOMIC_SET
#define CC_ATOMIC_SET(var,val) (var = val)
#endif
#ifndef CC_ATOMIC_GET
#define CC_ATOMIC_GET(var) (var)
#endif
#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
#endif

View File

@@ -0,0 +1,138 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for esc_coe.c
*/
#ifndef __esc_coe__
#define __esc_coe__
#include <cc.h>
typedef struct
{
uint16_t subindex;
uint16_t datatype;
uint16_t bitlength;
uint16_t flags;
const char *name;
uint32_t value;
void *data;
} _objd;
typedef struct
{
uint16_t index;
uint16_t objtype;
uint8_t maxsub;
uint8_t pad1;
const char *name;
const _objd *objdesc;
} _objectlist;
typedef struct
{
const _objd * obj;
const _objectlist * objectlistitem;
uint32_t offset;
} _SMmap;
#define OBJH_READ 0
#define OBJH_WRITE 1
#define OTYPE_DOMAIN 0x0002
#define OTYPE_DEFTYPE 0x0005
#define OTYPE_DEFSTRUCT 0x0006
#define OTYPE_VAR 0x0007
#define OTYPE_ARRAY 0x0008
#define OTYPE_RECORD 0x0009
#define DTYPE_BOOLEAN 0x0001
#define DTYPE_INTEGER8 0x0002
#define DTYPE_INTEGER16 0x0003
#define DTYPE_INTEGER32 0x0004
#define DTYPE_UNSIGNED8 0x0005
#define DTYPE_UNSIGNED16 0x0006
#define DTYPE_UNSIGNED32 0x0007
#define DTYPE_REAL32 0x0008
#define DTYPE_VISIBLE_STRING 0x0009
#define DTYPE_OCTET_STRING 0x000A
#define DTYPE_UNICODE_STRING 0x000B
#define DTYPE_INTEGER24 0x0010
#define DTYPE_UNSIGNED24 0x0016
#define DTYPE_INTEGER64 0x0015
#define DTYPE_UNSIGNED64 0x001B
#define DTYPE_REAL64 0x0011
#define DTYPE_PDO_MAPPING 0x0021
#define DTYPE_IDENTITY 0x0023
#define DTYPE_BITARR8 0x002D
#define DTYPE_BITARR16 0x002E
#define DTYPE_BITARR32 0x002F
#define DTYPE_BIT1 0x0030
#define DTYPE_BIT2 0x0031
#define DTYPE_BIT3 0x0032
#define DTYPE_BIT4 0x0033
#define DTYPE_BIT5 0x0034
#define DTYPE_BIT6 0x0035
#define DTYPE_BIT7 0x0036
#define DTYPE_BIT8 0x0037
#define DTYPE_ARRAY_OF_INT 0x0260
#define DTYPE_ARRAY_OF_SINT 0x0261
#define DTYPE_ARRAY_OF_DINT 0x0262
#define DTYPE_ARRAY_OF_UDINT 0x0263
#define ATYPE_Rpre 0x01
#define ATYPE_Rsafe 0x02
#define ATYPE_Rop 0x04
#define ATYPE_Wpre 0x08
#define ATYPE_Wsafe 0x10
#define ATYPE_Wop 0x20
#define ATYPE_RXPDO 0x40
#define ATYPE_TXPDO 0x80
#define ATYPE_BACKUP 0x100
#define ATYPE_SETTING 0x200
#define ATYPE_RO (ATYPE_Rpre | ATYPE_Rsafe | ATYPE_Rop)
#define ATYPE_WO (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_Wop)
#define ATYPE_RW (ATYPE_RO | ATYPE_WO)
#define ATYPE_RWpre (ATYPE_Wpre | ATYPE_RO)
#define ATYPE_RWop (ATYPE_Wop | ATYPE_RO)
#define ATYPE_RWpre_safe (ATYPE_Wpre | ATYPE_Wsafe | ATYPE_RO)
#define TX_PDO_OBJIDX 0x1c13
#define RX_PDO_OBJIDX 0x1c12
#define COMPLETE_ACCESS_FLAG (1 << 15)
void ESC_coeprocess (void);
int16_t SDO_findsubindex (int32_t nidx, uint8_t subindex);
int32_t SDO_findobject (uint16_t index);
uint16_t sizeOfPDO (uint16_t index, int * nmappings, _SMmap * sm, int max_mappings);
void COE_initDefaultValues (void);
void COE_pdoPack (uint8_t * buffer, int nmappings, _SMmap * sm);
void COE_pdoUnpack (uint8_t * buffer, int nmappings, _SMmap * sm);
uint8_t COE_maxSub (uint16_t index);
extern uint32_t ESC_download_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
extern uint32_t ESC_download_pre_objecthandler (uint16_t index,
uint8_t subindex,
void * data,
size_t size,
uint16_t flags);
extern uint32_t ESC_upload_pre_objecthandler (uint16_t index,
uint8_t subindex,
void * data,
size_t *size,
uint16_t flags);
extern uint32_t ESC_upload_post_objecthandler (uint16_t index, uint8_t subindex, uint16_t flags);
extern const _objectlist SDOobjects[];
#endif

View File

@@ -0,0 +1,80 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* ESI EEPROM emulator module.
*/
#include "cc.h"
#include "esc.h"
#include "esc_eep.h"
#include <string.h>
static uint8_t eep_buf[8];
/** EPP periodic task of ESC side EEPROM emulation.
*
*/
void EEP_process (void)
{
eep_stat_t stat;
/* check for eeprom event */
if ((ESCvar.ALevent & ESCREG_ALEVENT_EEP) == 0) {
return;
}
while (1) {
/* read eeprom status */
ESC_read (ESCREG_EECONTSTAT, &stat, sizeof (eep_stat_t));
stat.contstat.reg = etohs(stat.contstat.reg);
stat.addr = etohl(stat.addr);
/* check busy flag, exit if job finished */
if (!stat.contstat.bits.busy) {
return;
}
/* clear error bits */
stat.contstat.bits.csumErr = 0;
stat.contstat.bits.eeLoading = 0;
stat.contstat.bits.ackErr = 0;
stat.contstat.bits.wrErr = 0;
/* process commands */
switch (stat.contstat.bits.cmdReg) {
case EEP_CMD_IDLE:
break;
case EEP_CMD_READ:
case EEP_CMD_RELOAD:
/* handle read request */
if (EEP_read (stat.addr * 2U /* sizeof(uint16_t) */, eep_buf, EEP_READ_SIZE) != 0) {
stat.contstat.bits.ackErr = 1;
} else {
ESC_write (ESCREG_EEDATA, eep_buf, EEP_READ_SIZE);
}
break;
case EEP_CMD_WRITE:
/* handle write request */
ESC_read (ESCREG_EEDATA, eep_buf, EEP_WRITE_SIZE);
if (EEP_write (stat.addr * 2U /* sizeof(uint16_t) */, eep_buf, EEP_WRITE_SIZE) != 0) {
stat.contstat.bits.ackErr = 1;
}
break;
default:
stat.contstat.bits.ackErr = 1;
}
/* acknowledge command */
stat.contstat.reg = htoes(stat.contstat.reg);
ESC_write (ESCREG_EECONTSTAT, &stat.contstat.reg, sizeof(uint16_t));
}
}

View File

@@ -0,0 +1,77 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for esc_eep.c
*/
#ifndef __esc_eep__
#define __esc_eep__
#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 0x4
/* read/write size */
#define EEP_READ_SIZE 8
#define EEP_WRITE_SIZE 2
/* CONSTAT register content */
typedef struct CC_PACKED
{
union {
uint16_t reg;
struct {
uint8_t wrEnable:1;
uint8_t reserved:4;
uint8_t eeEmulated:1;
uint8_t eightByteRead:1;
uint8_t twoByteAddr:1;
uint8_t cmdReg:3;
uint8_t csumErr:1;
uint8_t eeLoading:1;
uint8_t ackErr:1;
uint8_t wrErr:1;
uint8_t busy:1;
} bits;
} contstat;
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);
/* From hardware file */
void EEP_init (void);
int8_t EEP_read (uint32_t addr, uint8_t *data, uint16_t size);
int8_t EEP_write (uint32_t addr, uint8_t *data, uint16_t size);
#endif

View File

@@ -0,0 +1,68 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for esc_eoe.c
*/
#ifndef __esc_eoe__
#define __esc_eoe__
#include <cc.h>
typedef struct eoe_pbuf
{
/** Pointer to frame buffer type used by a TCP/IP stack. (Not mandatory) */
void * pbuf;
/** Pointer to frame buffer to send or read from */
uint8_t * payload;
/** Length of data in frame buffer */
size_t len;
} eoe_pbuf_t;
typedef struct eoe_cfg
{
/** Callback function to get a frame buffer for storage of received frame */
void (*get_buffer) (eoe_pbuf_t * ebuf);
/** Callback function to free a frame buffer */
void (*free_buffer) (eoe_pbuf_t * ebuf);
/** Callback function to read local settings and update EtherCAT variables
* to be delivered to the EtherCAT Master
*/
int (*load_eth_settings) (void);
/** Callback function to read settings provided by the EtherCAT master
* and store to local settings.
*/
int (*store_ethernet_settings) (void);
/** Callback to frame receive function in TCP(IP stack,
* caller should free the buffer
* */
void (*handle_recv_buffer) (uint8_t port, eoe_pbuf_t * ebuf);
/** Callback to fetch a buffer to send */
int (*fetch_send_buffer) (uint8_t port, eoe_pbuf_t * ebuf);
/** Callback to notify the application fragment sent */
void (*fragment_sent_event) (void);
} eoe_cfg_t;
int EOE_ecat_get_mac (uint8_t port, uint8_t mac[]);
int EOE_ecat_get_ip (uint8_t port, uint32_t * ip);
int EOE_ecat_get_subnet (uint8_t port, uint32_t * subnet);
int EOE_ecat_get_gateway (uint8_t port, uint32_t * default_gateway);
int EOE_ecat_get_dns_ip (uint8_t port, uint32_t * dns_ip);
int EOE_ecat_get_dns_name (uint8_t port, char * dns_name);
int EOE_ecat_set_mac (uint8_t port, uint8_t mac[]);
int EOE_ecat_set_ip (uint8_t port, uint32_t ip);
int EOE_ecat_set_subnet (uint8_t port, uint32_t subnet);
int EOE_ecat_set_gateway (uint8_t port, uint32_t default_gateway);
int EOE_ecat_set_dns_ip (uint8_t port, uint32_t dns_ip);
int EOE_ecat_set_dns_name (uint8_t port, char * dns_name);
void EOE_config (eoe_cfg_t * cfg);
void EOE_init (void);
void ESC_eoeprocess (void);
void ESC_eoeprocess_tx (void);
#endif

View File

@@ -0,0 +1,636 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* File over EtherCAT (FoE) module.
*/
#include <cc.h>
#include "esc.h"
#include "esc_foe.h"
#include <string.h>
/** \file
* \brief
* File over EtherCAT (FoE) module.
*
* FOE read / write and FOE service functions
*/
//define if FOE_read should be supported
//#define FOE_READ_SUPPORTED
/** Variable holding current filename read at FOE Open.
*/
static char foe_file_name[FOE_FN_MAX + 1];
/** Main FoE configuration pointer data array. Structure is allocated and filled
* by the application defining what preferences it requires.
*/
static foe_cfg_t * foe_cfg;
/** Pointer to current file configuration item used by FoE.
*/
static foe_file_cfg_t * foe_file;
/** Main FoE status data array. Structure gets filled with current status
* variables during FoE usage.
*/
static _FOEvar FOEvar;
/** Validate a write or read request by checking filename and password.
*
* @param[in] name = Filename
* @param[in] num_chars = Length of filename
* @param[in] pass = Numeric variable of password
* @param[in] op = Request op-code
* @return 0= if we succeed, FOE_ERR_NOTFOUND something wrong with filename or
* password
*/
static uint32_t FOE_fopen (char *name, uint8_t num_chars, uint32_t pass, uint8_t op)
{
uint32_t i;
/* Unpack the file name into characters we can look at. */
if (num_chars > FOE_FN_MAX)
{
num_chars = FOE_FN_MAX;
}
for (i = 0; i < num_chars; i++)
{
foe_file_name[i] = name[i];
}
foe_file_name[i] = '\0';
/* Figure out what file they're talking about. */
for (i = 0; i < foe_cfg->n_files; i++)
{
if (0 == strncmp (foe_file_name, foe_cfg->files[i].name, num_chars))
{
if (pass != foe_cfg->files[i].filepass)
{
return FOE_ERR_NORIGHTS;
}
if (op == FOE_OP_WRQ &&
(foe_cfg->files[i].write_only_in_boot) &&
(ESCvar.ALstatus != ESCboot))
{
return FOE_ERR_NOTINBOOTSTRAP;
}
foe_file = &foe_cfg->files[i];
foe_file->address_offset = 0;
foe_file->total_size = 0;
switch (op)
{
case FOE_OP_RRQ:
{
FOEvar.fposition = 0;
FOEvar.fend = foe_cfg->files[i].max_data;
return 0;
}
case FOE_OP_WRQ:
{
FOEvar.fposition = 0;
FOEvar.fend = foe_cfg->files[i].max_data;
return 0;
}
}
}
}
return FOE_ERR_NOTFOUND;
}
#ifdef FOE_READ_SUPPORTED
/** Function writing local data to mailbox buffer to be sent as next FoE frame.
* It will try to fill the Mailbox buffer available if there is enough data
* left to read.
*
* @param[in] data = pointer to buffer
* @param[in] maxlength = max length of data possible to read, controlled by
* Mailbox - FoE and Mailbox frame headers.
* @return Number of copied bytes.
*/
static uint32_t FOE_fread (uint8_t * data, uint32_t maxlength)
{
uint32_t ncopied = 0;
while (maxlength && (FOEvar.fend - FOEvar.fposition))
{
maxlength--;
*(data++) = foe_cfg->fbuffer[FOEvar.fposition++];
ncopied++;
}
return ncopied;
}
#endif
/** Function reading mailbox buffer to local buffer to be handled by
* application write hook. Ex. flash routine used by software update.
* It will consume the buffer and call the write hook every time the configured
* flush buffer limit is reached.
*
*
* @param[in] data = Pointer to buffer
* @param[in] length = Length of data to read
* @return Number of copied bytes.
*/
static uint32_t FOE_fwrite (uint8_t *data, uint32_t length)
{
uint32_t ncopied = 0;
uint32_t failed = 0;
DPRINT("FOE_fwrite\n");
FOEvar.fprevposition = FOEvar.fposition;
while (length && (FOEvar.fend - FOEvar.fposition) && !failed)
{
length--;
foe_cfg->fbuffer[FOEvar.fbufposition++] = *(data++);
if(FOEvar.fbufposition >= foe_cfg->buffer_size)
{
failed = foe_file->write_function (foe_file, foe_cfg->fbuffer, FOEvar.fbufposition);
FOEvar.fbufposition = 0;
foe_file->address_offset += foe_cfg->buffer_size;
}
FOEvar.fposition++;
if(failed)
{
DPRINT("Failed FOE_fwrite ncopied=%"PRIu32"\n", ncopied);
}
else
{
ncopied++;
}
}
foe_file->total_size += ncopied;
DPRINT("FOE_fwrite END with : %"PRIu32"\n",ncopied);
return ncopied;
}
/** Function handling the final FOE_fwrite when we close up regardless
* if we have filled the buffers or not.
*
* @return Number of copied bytes on success, 0= if failed.
*/
static uint32_t FOE_fclose (void)
{
uint32_t failed = 0;
DPRINT("FOE_fclose\n");
failed = foe_file->write_function (foe_file, foe_cfg->fbuffer, FOEvar.fbufposition);
foe_file->address_offset += FOEvar.fbufposition;
FOEvar.fbufposition = 0;
return failed;
}
/** Initialize by clearing all current status variables.
*
*/
void FOE_init ()
{
DPRINT("FOE_init\n");
FOEvar.foepacket = 0;
FOEvar.foestate = FOE_READY;
FOEvar.fposition = 0;
FOEvar.fprevposition = 0;
FOEvar.fbufposition = 0;
}
/** Function for sending an FOE abort frame.
*
* @param[in] code = abort code
*/
static void FOE_abort (uint32_t code)
{
_FOE *foembx;
uint8_t mbxhandle;
if (code)
{
/* Send back an error packet. */
mbxhandle = ESC_claimbuffer ();
if (mbxhandle)
{
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);
MBXcontrol[mbxhandle].state = MBXstate_outreq;
}
/* Nothing we can do if we can't get an outbound mailbox. */
}
DPRINT("FOE_abort: 0x%"PRIX32"\n", code);
FOE_init ();
}
#ifdef FOE_READ_SUPPORTED
/** Sends an FoE data frame, returning the number of data bytes
* written or an error number.
* Error numbers will be greater than FOE_DATA_SIZE.
* @param[in] data = pointer to buffer
* @param[in] length = length of data to read
* @return Number of data bytes written or an error number. Error numbers
* will be greater than FOE_DATA_SIZE.
*/
static uint32_t FOE_send_data_packet ()
{
_FOE *foembx;
uint32_t data_len;
uint8_t mbxhandle;
mbxhandle = ESC_claimbuffer ();
if (mbxhandle)
{
foembx = (_FOE *) &MBX[mbxhandle * ESC_MBXSIZE];
data_len = FOE_fread (foembx->data, ESC_FOE_DATA_SIZE);
foembx->foeheader.opcode = FOE_OP_DATA;
foembx->foeheader.packetnumber = htoel (FOEvar.foepacket);
FOEvar.foepacket++;
foembx->mbxheader.length = htoes (data_len + ESC_FOEHSIZE);
foembx->mbxheader.mbxtype = MBXFOE;
/* Mark the outbound mailbox as filled. */
MBXcontrol[mbxhandle].state = MBXstate_outreq;
return data_len;
}
else
{
return FOE_ERR_PROGERROR;
}
}
#endif
/** Sends an FoE ack data frame.
* @return 0= or error number.
*/
static uint32_t FOE_send_ack ()
{
_FOE *foembx;
uint8_t mbxhandle;
mbxhandle = ESC_claimbuffer ();
if (mbxhandle)
{
DPRINT("FOE_send_ack\n");
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);
FOEvar.foepacket++;
MBXcontrol[mbxhandle].state = MBXstate_outreq;
return 0;
}
else
{
DPRINT("ERROR:FOE_send_ack\n");
return FOE_ERR_PROGERROR;
}
}
/* Handlers for various FoE states. */
#ifdef FOE_READ_SUPPORTED
/** FoE read request handler. Starts with Initialize, Open and Sending one frame.
* When first frame have been sent we will send data from Ack.
* On error we will send FOE Abort.
*
*/
static void FOE_read ()
{
_FOE *foembx;
uint32_t password;
uint32_t res;
uint8_t data_len;
if (FOEvar.foestate != FOE_READY)
{
FOE_abort (FOE_ERR_ILLEGAL);
return;
}
FOE_init ();
foembx = (_FOE *) &MBX[0];
/* Get the length of the file name in octets. */
data_len = (uint8_t)(etohs (foembx->mbxheader.length) - ESC_FOEHSIZE);
password = etohl (foembx->foeheader.password);
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_RRQ);
if (res == 0)
{
FOEvar.foepacket = 1;
/*
* Attempt to send the packet
*/
res = FOE_send_data_packet ();
if (res <= ESC_FOE_DATA_SIZE)
{
FOEvar.foestate = FOE_WAIT_FOR_ACK;
}
else
{
FOE_abort (res);
}
}
else
{
FOE_abort (res);
}
}
/** FoE data ack handler. Will continue sending next frame until finished.
* On error we will send FOE Abort.
*/
static void FOE_ack ()
{
uint32_t res;
/* Make sure we're able to take this. */
if (FOEvar.foestate == FOE_WAIT_FOR_FINAL_ACK)
{
/* Move us back to ready state. */
FOE_init ();
return;
}
else if (FOEvar.foestate != FOE_WAIT_FOR_ACK)
{
FOE_abort (FOE_ERR_ILLEGAL);
return;
}
res = FOE_send_data_packet ();
if (res < ESC_FOE_DATA_SIZE)
{
FOEvar.foestate = FOE_WAIT_FOR_FINAL_ACK;
}
else if (res >= FOE_ERR_NOTDEFINED)
{
FOE_abort (FOE_ERR_PROGERROR);
}
}
#endif
/** FoE write request handler. Starts with Initialize, Open and Ack that we can/will
* receive data. On error we will send FOE Abort.
*
*/
static void FOE_write ()
{
_FOE *foembx;
uint32_t password;
uint32_t res;
uint8_t data_len;
if (FOEvar.foestate != FOE_READY)
{
FOE_abort (FOE_ERR_ILLEGAL);
return;
}
FOE_init ();
foembx = (_FOE *) &MBX[0];
data_len = (uint8_t)(etohs (foembx->mbxheader.length) - ESC_FOEHSIZE);
password = etohl (foembx->foeheader.password);
/* Get an address we can write the file to, if possible. */
res = FOE_fopen (foembx->filename, data_len, password, FOE_OP_WRQ);
DPRINT("%s %sOK, file \"%s\"\n", __func__, (res == 0) ? "" : "N", foe_file_name);
if (res == 0)
{
res = FOE_send_ack ();
if (res)
{
FOE_abort (res);
}
else
{
FOEvar.foestate = FOE_WAIT_FOR_DATA;
}
}
else
{
FOE_abort (res);
}
}
/** FoE data request handler. Validates and reads data until we're finished. Every
* read frame followed by an Ack frame. On error we will send FOE Abort.
*
*/
static void FOE_data ()
{
_FOE *foembx;
uint32_t packet;
uint32_t data_len, ncopied;
uint32_t res;
if(FOEvar.foestate != FOE_WAIT_FOR_DATA)
{
FOE_abort(FOE_ERR_ILLEGAL);
return;
}
foembx = (_FOE*)&MBX[0];
data_len = etohs(foembx->mbxheader.length) - ESC_FOEHSIZE;
packet = etohl(foembx->foeheader.packetnumber);
if (packet != FOEvar.foepacket)
{
DPRINT("FOE_data packet error, packet: %"PRIu32", foeheader.packet: %"PRIu32"\n",
packet,
FOEvar.foepacket);
FOE_abort (FOE_ERR_PACKETNO);
}
else if (data_len == 0)
{
DPRINT("FOE_data completed\n");
FOE_fclose ();
res = FOE_send_ack ();
FOE_init ();
}
else if (FOEvar.fposition + data_len > FOEvar.fend)
{
DPRINT("FOE_data disk full\n");
FOE_abort (FOE_ERR_DISKFULL);
}
else
{
ncopied = FOE_fwrite (foembx->data, data_len);
if (!ncopied)
{
DPRINT("FOE_data no copied\n");
FOE_abort (FOE_ERR_PROGERROR);
}
else if (data_len == ESC_FOE_DATA_SIZE)
{
DPRINT("FOE_data data_len == FOE_DATA_SIZE\n");
if (ncopied != data_len)
{
DPRINT("FOE_data only %"PRIu32" of %"PRIu32" copied\n",ncopied, data_len);
FOE_abort (FOE_ERR_PROGERROR);
}
res = FOE_send_ack ();
if (res)
{
FOE_abort (res);
}
}
else
{
if ((ncopied != data_len) || FOE_fclose ())
{
DPRINT("FOE_fclose failed to write extra buffer\n");
FOE_abort (FOE_ERR_PROGERROR);
}
else
{
DPRINT("FOE_data completed\n");
res = FOE_send_ack ();
FOE_init ();
}
}
}
}
#ifdef FOE_READ_SUPPORTED
/** FoE read request busy handler. Send an Ack of last frame again. On error
* we will send FOE Abort.
*
*/
static void FOE_busy ()
{
/* Only valid if we're servicing a read request. */
if (FOEvar.foestate != FOE_WAIT_FOR_ACK)
{
FOE_abort (FOE_ERR_ILLEGAL);
}
else
{
/* Send the last part again. */
FOEvar.fposition = FOEvar.fprevposition;
FOEvar.foepacket--;
FOE_ack ();
}
}
#endif
/** FoE error requesthandler. Send an FOE Abort.
*
*/
static void FOE_error ()
{
/* Master panic! abort the transfer. */
FOE_abort (0);
}
/** Function copying the application configuration variable
* to the FoE module local pointer variable.
*
* @param[in] cfg = Pointer to by the Application static declared
* configuration variable holding application specific details.
*/
void FOE_config (foe_cfg_t * cfg)
{
foe_cfg = cfg;
}
/** Main FoE function checking the status on current mailbox buffers carrying
* data, distributing the mailboxes to appropriate FOE functions depending
* on requested opcode.
* On Error an FoE Error or FoE Abort will be sent.
*/
void ESC_foeprocess (void)
{
_MBXh *mbh;
_FOE *foembx;
if (ESCvar.MBXrun == 0)
{
return;
}
if (!ESCvar.xoe && (MBXcontrol[0].state == MBXstate_inclaim))
{
mbh = (_MBXh *) &MBX[0];
if (mbh->mbxtype == MBXFOE)
{
ESCvar.xoe = MBXFOE;
}
}
if (ESCvar.xoe == MBXFOE)
{
foembx = (_FOE *) &MBX[0];
/* Verify the size of the file data. */
if (etohs (foembx->mbxheader.length) < ESC_FOEHSIZE)
{
FOE_abort (MBXERR_SIZETOOSHORT);
}
else
{
switch (foembx->foeheader.opcode)
{
case FOE_OP_WRQ:
{
DPRINT("FOE_OP_WRQ\n");
FOE_write ();
break;
}
case FOE_OP_DATA:
{
DPRINT("FOE_OP_DATA\n");
FOE_data ();
break;
}
#ifdef FOE_READ_SUPPORTED
case FOE_OP_RRQ:
{
DPRINT("FOE_OP_RRQ\n");
FOE_read ();
break;
}
case FOE_OP_ACK:
{
DPRINT("FOE_OP_ACK\n");
FOE_ack ();
break;
}
case FOE_OP_BUSY:
{
DPRINT("FOE_OP_BUSY\n");
FOE_busy ();
break;
}
#endif
case FOE_OP_ERR:
{
DPRINT("FOE_OP_ERR\n");
FOE_error ();
break;
}
default:
{
DPRINT("FOE_ERR_NOTDEFINED\n");
FOE_abort (FOE_ERR_NOTDEFINED);
break;
}
}
}
MBXcontrol[0].state = MBXstate_idle;
ESCvar.xoe = 0;
}
}

View File

@@ -0,0 +1,77 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
/** \file
* \brief
* Headerfile for esc_foe.c
*/
#ifndef __esc_foe__
#define __esc_foe__
#include <cc.h>
/** Maximum number of characters allowed in a file name. */
#define FOE_FN_MAX 31
typedef struct foe_file_cfg foe_file_cfg_t;
struct foe_file_cfg
{
/** Name of file to receive from master */
const char * name;
/** Size of file,sizeof data we can recv */
uint32_t max_data;
/** Where to store the data initially */
uint32_t dest_start_address;
/** Current address during write of file */
uint32_t address_offset;
/** Calculated size of file received */
uint32_t total_size;
/** FoE password */
uint32_t filepass;
/** This file can be written only in BOOT state. Intended for FW files */
uint8_t write_only_in_boot;
/** for feature use */
uint32_t padding:24;
/** Pointer to application foe write function */
uint32_t (*write_function) (foe_file_cfg_t * self, uint8_t * data, size_t length);
};
typedef struct foe_cfg
{
/** Allocate static in caller func to fit buffer_size */
uint8_t * fbuffer;
/** Buffer size before we flush to destination */
uint32_t buffer_size;
/** Number of files used in firmware update */
uint32_t n_files;
/** Pointer to files configured to be used by FoE */
foe_file_cfg_t * files;
} foe_cfg_t;
typedef struct CC_PACKED
{
/** Current FoE state, ex. Waiting for ACK, Waiting for DATA */
uint8_t foestate;
/** Current file buffer position, evaluated against foe file buffer size
* when to flush
*/
uint16_t fbufposition;
/** Frame number in read or write sequence */
uint32_t foepacket;
/** Current position in file to be handled by FoE request */
uint32_t fposition;
/** Previous position in file to be handled by FoE request */
uint32_t fprevposition;
/** End position of allocated disk space for FoE requested file */
uint32_t fend;
} _FOEvar;
/* Initializes FoE state. */
void FOE_config (foe_cfg_t * cfg);
void FOE_init (void);
void ESC_foeprocess (void);
#endif

View File

@@ -0,0 +1,216 @@
/*
* 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 <string.h>
#include "esc.h"
#include "spi_utils.h"
#include "rst.h"
#define MAX_READ_SIZE 128
#define ESC_CMD_READ 0x02
#define ESC_CMD_READWS 0x03
#define ESC_CMD_WRITE 0x04
#define ESC_CMD_NOP 0x00
#define ESC_TERM 0xff
#define ESC_NEXT 0x00
#define ESCREG_PDI_CONTROL 0x0140
#define ESCREG_ESC_CONFIG 0x0141
#define DC_SYNC_OUT 0x04
#define ESCREG_CYCLIC_UNIT_CONTROL 0x0980
#define SYNC_OUT_UNIT_CONTROL_MASK 0x01
#define SYNC_OUT_ECAT_CONTROL 0x00
#define SYNC_OUT_PDI_CONTROL 0x01
#define ESCREG_SYNC0_CYCLE_TIME 0x09A0
#define ESCREG_SYNC_START_TIME 0x0990
// measured with 21MHz SPI PDI
#define SYNC_START_OFFSET 2342840
static int et1100 = -1;
static uint8_t read_termination[MAX_READ_SIZE] = {0};
#define GPIO_ECAT_RESET 1 /* specific function to hold ESC reset on startup \
* when emulating EEPROM \
*/
static void esc_address(uint16_t address, uint8_t command)
{
/* Device is selected already.
* We use 2 bytes addressing.
*/
uint8_t data[2];
/* address 12:5 */
data[0] = (address >> 5);
/* address 4:0 and cmd 2:0 */
data[1] = ((address & 0x1F) << 3) | command;
/* Write (and read AL interrupt register) */
spi_bidirectionally_transfer(et1100, (uint8_t *)&ESCvar.ALevent,
data, sizeof(data));
ESCvar.ALevent = etohs(ESCvar.ALevent);
}
/** 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 (len > MAX_READ_SIZE)
{
return;
}
/* Select device. */
spi_select(et1100);
/* Write address and command to device. */
esc_address(address, ESC_CMD_READ);
/* Here we want to read data and keep MOSI low (0x00) during
* all bytes except the last one where we want to pull it high (0xFF).
* Read (and write termination bytes).
*/
spi_bidirectionally_transfer(et1100, buf, read_termination + (MAX_READ_SIZE - len), len);
/* Un-select device. */
spi_unselect(et1100);
}
/** 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)
{
/* Select device. */
spi_select(et1100);
/* Write address and command to device. */
esc_address(address, ESC_CMD_WRITE);
/* Write data. */
spi_write(et1100, buf, len);
/* Un-select device. */
spi_unselect(et1100);
}
static void task_delay(uint32_t time_us)
{
#define DELAY_1_uS 168 // todo tweak to used clock speed
uint32_t delay_ticks = DELAY_1_uS * time_us;
for (int32_t i = 0; i < delay_ticks; ++i)
{
// do nothing
}
}
void ESC_reset(void)
{
volatile uint32_t timeout;
DPRINT("esc_reset_started\n");
rst_low();
task_delay(1000);
rst_check_start();
while (timeout < 10000000)
{
/* ECAT releases resetpin, typically takes 40 us
Reset to operational PDI is max 70 ms */
if (is_esc_reset())
{
rst_high();
break; // OK
}
timeout++;
task_delay(30);
}
DPRINT("esc_reset_ended\n");
}
void ESC_init(const esc_cfg_t *config)
{
rst_setup();
rst_high();
spi_setup();
et1100 = 1;
read_termination[MAX_READ_SIZE - 1] = 0xFF;
// uint8_t device_symbol = 0;
// while (device_symbol == 0)
// {
// ESC_read(et1100, (void *)&device_symbol, sizeof(uint8_t));
// if ((device_symbol != 0) || (device_symbol != 0xFF))
// {
// DPRINT("ESC init successful");
// }
// }
// task_delay(1000); // allow ESC to load EEPROM, or if EEP_DONE can be read
// then wait while EEP_DONE is low.
}
/** ESC enable Distributed Clocks (DC)
*
* @return SYNC0 cycle time
*/
uint32_t ESC_enable_DC()
{
uint8_t data = 0x00;
// check DC Sync Out bit: 0x140:10
ESC_read(ESCREG_ESC_CONFIG, &data, sizeof(data));
if (!(data & DC_SYNC_OUT))
{
return 0; // DC sync is not enabled in ESI
}
// read set SYNC0 Cycle Time from 0x09A0
uint32_t setsync0cycleTime = 0;
ESC_read(ESCREG_SYNC0_CYCLE_TIME, &setsync0cycleTime, sizeof(uint32_t));
setsync0cycleTime = etohl(setsync0cycleTime);
// check Sync Unit assign 0x0980:0 ( 0 for ECAT, 1 for PDI )
ESC_read(ESCREG_CYCLIC_UNIT_CONTROL, &data, sizeof(data));
if (data == SYNC_OUT_PDI_CONTROL)
{
// Sync Unit assigned to PDI, configuration needs to be finished by slave
// set sync start time: read system time, add offset for writing start time and activation
ESC_read(ESCREG_LOCALTIME, (void *)&ESCvar.Time, sizeof(ESCvar.Time));
ESCvar.Time = etohl(ESCvar.Time);
uint32_t startTime = ESCvar.Time + SYNC_START_OFFSET;
ESC_write(ESCREG_SYNC_START_TIME, &startTime, sizeof(startTime));
// activate cyclic operation and SYNC0
ESC_read(ESCREG_SYNC_ACT, &data, sizeof(data));
data = data | ESCREG_SYNC_ACT_ACTIVATED | ESCREG_SYNC_SYNC0_EN;
ESC_write(ESCREG_SYNC_ACT, &data, sizeof(data));
data = 0x00;
while (!(data & (ESCREG_SYNC_ACT_ACTIVATED | ESCREG_SYNC_SYNC0_EN)))
{
ESC_read(ESCREG_SYNC_ACT, &data, sizeof(data));
}
}
return setsync0cycleTime;
}

View File

@@ -0,0 +1,32 @@
#include <Arduino.h>
#include "rst.h"
void rst_setup(void)
{
/* Set RSTN as ouput */
pinMode(ESC_Pin_RSTN, OUTPUT);
rst_high();
}
void rst_low(void)
{ /* Set RSTN line low */
digitalWrite(ESC_Pin_RSTN, LOW);
}
void rst_high(void)
{
/* Set RSTN line high */
digitalWrite(ESC_Pin_RSTN, HIGH);
}
void rst_check_start(void)
{
/* Setup NRST as GPIO input and pull it high */
pinMode(ESC_Pin_RSTN, INPUT_PULLUP);
}
uint8_t is_esc_reset(void)
{
/* Check if ESC pulled RSTN line up */
return digitalRead(ESC_Pin_RSTN);
}

View File

@@ -0,0 +1,21 @@
#ifndef __RST_H__
#define __RST_H__
#define ESC_Pin_RSTN PB12
#ifdef __cplusplus
extern "C" {
#endif
void rst_setup(void);
void rst_low(void);
void rst_high(void);
void rst_check_start(void);
uint8_t is_esc_reset(void);
#ifdef __cplusplus
}
#endif
#endif /* __RST_H__ */

View File

@@ -0,0 +1,66 @@
#include "spi_utils.h"
// #include <Arduino.h>
#include <SPI.h>
char SCS = ESC_GPIO_Pin_CS;
void spi_setup(void)
{
SPI.begin();
pinMode(SCS, OUTPUT);
spi_unselect(0);
delay(100);
SPI.beginTransaction(SPISettings(SPIX_ESC_SPEED, MSBFIRST, SPI_MODE3));
}
void spi_select (int8_t board)
{
// Soft CSN
#if SCS_ACTIVE_POLARITY == SCS_LOW
digitalWrite(SCS, LOW);
#endif
}
void spi_unselect (int8_t board)
{
// Soft CSN
#if SCS_ACTIVE_POLARITY == SCS_LOW
digitalWrite(SCS, HIGH);
#endif
}
inline static uint8_t spi_transfer_byte(uint8_t byte)
{
return SPI.transfer(byte);
// AVR will need handling last byte transfer difference,
// but then again they pobably wont even fit EtherCAT stack in RAM
// so no need to care for now
}
void spi_write (int8_t board, uint8_t *data, uint8_t size)
{
for(int i = 0; i < size; ++i)
{
spi_transfer_byte(data[i]);
}
}
void spi_read (int8_t board, uint8_t *result, uint8_t size)
{
for(int i = 0; i < size; ++i)
{
result[i] = spi_transfer_byte(DUMMY_BYTE);
}
}
void spi_bidirectionally_transfer (int8_t board, uint8_t *result, uint8_t *data, uint8_t size)
{
for(int i = 0; i < size; ++i)
{
result[i] = spi_transfer_byte(data[i]);
}
}

View File

@@ -0,0 +1,31 @@
#ifndef SRC_APP_SPI_H_
#define SRC_APP_SPI_H_
#include <stdint.h>
#define SCS_LOW LOW
#define SCS_HIGH HIGH
#define SCS_ACTIVE_POLARITY SCS_LOW
// 80 MHz
#define SPIX_ESC_SPEED 80000000
#define ESC_GPIO_Pin_CS PC4
#define DUMMY_BYTE 0xFF
#ifdef __cplusplus
extern "C" {
#endif
void spi_setup(void);
void spi_select (int8_t board);
void spi_unselect (int8_t board);
void spi_write (int8_t board, uint8_t *data, uint8_t size);
void spi_read (int8_t board, uint8_t *result, uint8_t size);
void spi_bidirectionally_transfer (int8_t board, uint8_t *result, uint8_t *data, uint8_t size);
#ifdef __cplusplus
}
#endif
#endif /* SRC_APP_SPI_H_ */

View File

@@ -0,0 +1,91 @@
/*
* 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
#ifdef __cplusplus
extern "C"
{
#endif
#include <assert.h>
#include <stdint.h>
#include <stddef.h>
#include <inttypes.h>
#include <sys/param.h>
#ifdef __linux__
#include <endian.h>
#else
#include <machine/endian.h>
#endif
#ifndef MIN
#define MIN(a,b) (((a)<(b))?(a):(b))
#endif
#ifndef MAX
#define MAX(a,b) (((a)>(b))?(a):(b))
#endif
#define CC_PACKED_BEGIN
#define CC_PACKED_END
#define CC_PACKED __attribute__((packed))
#define CC_ALIGNED(n) __attribute__((aligned (n)))
#ifdef __rtk__
#include <kern/assert.h>
#define CC_ASSERT(exp) ASSERT (exp)
#else
#define CC_ASSERT(exp) assert (exp)
#endif
#define CC_STATIC_ASSERT(exp) _Static_assert (exp, "")
#define CC_DEPRECATED __attribute__((deprecated))
#define CC_SWAP32(x) __builtin_bswap32 (x)
#define CC_SWAP16(x) __builtin_bswap16 (x)
#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 ((uint16_t)(x))
#define htoel(x) CC_SWAP32 ((uint32_t)(x))
#else
#define htoes(x) ((uint16_t)(x))
#define htoel(x) ((uint32_t)(x))
#endif
#define etohs(x) htoes (x)
#define etohl(x) htoel (x)
#if BYTE_ORDER == LITTLE_ENDIAN
#define EC_LITTLE_ENDIAN
#else
#define EC_BIG_ENDIAN
#endif
#ifdef ESC_DEBUG
#ifdef __rtk__
#include <kern/rprint.h>
#define DPRINT(...) rprintp ("soes: "__VA_ARGS__)
#else
#include <stdio.h>
#define DPRINT(...) printf ("soes: "__VA_ARGS__)
#endif
#else
#define DPRINT(...)
#endif
#ifdef __cplusplus
}
#endif
#endif /* CC_H */

View File

@@ -0,0 +1,4 @@
/usr/bin/xinit: XFree86_VT property unexpectedly has 0 items instead of 1
(EE) Failed to open authorization file "/tmp/.xas268255516136.AzWqmP": No such file or directory
xterm: fatal IO error 11 (Resursen tillfälligt otillgänglig) or KillClient on X server ":20"

View File

@@ -0,0 +1,151 @@
/*
* Licensed under the GNU General Public License version 2 with exceptions. See
* LICENSE file in the project root for full license information
*/
#ifndef __options__
#define __options__
/* User-defined options, Options defined here will override default values */
#include "ecat_options.h"
/* FoE support */
#ifndef USE_FOE
#define USE_FOE 1
#endif
/* EoE support */
#ifndef USE_EOE
#define USE_EOE 1
#endif
#ifndef MBXSIZE
#define MBXSIZE 128
#endif
#ifndef MBXSIZEBOOT
#define MBXSIZEBOOT 128
#endif
#ifndef MBXBUFFERS
#define MBXBUFFERS 3
#endif
#ifndef PREALLOC_FACTOR
#define PREALLOC_FACTOR 3
#endif
#ifndef MBX0_sma
#define MBX0_sma 0x1000
#endif
#ifndef MBX0_sml
#define MBX0_sml MBXSIZE
#endif
#ifndef MBX0_sme
#define MBX0_sme MBX0_sma+MBX0_sml-1
#endif
#ifndef MBX0_smc
#define MBX0_smc 0x26
#endif
#ifndef MBX1_sma
#define MBX1_sma MBX0_sma+MBX0_sml
#endif
#ifndef MBX1_sml
#define MBX1_sml MBXSIZE
#endif
#ifndef MBX1_sme
#define MBX1_sme MBX1_sma+MBX1_sml-1
#endif
#ifndef MBX1_smc
#define MBX1_smc 0x22
#endif
#ifndef MBX0_sma_b
#define MBX0_sma_b 0x1000
#endif
#ifndef MBX0_sml_b
#define MBX0_sml_b MBXSIZEBOOT
#endif
#ifndef MBX0_sme_b
#define MBX0_sme_b MBX0_sma_b+MBX0_sml_b-1
#endif
#ifndef MBX0_smc_b
#define MBX0_smc_b 0x26
#endif
#ifndef MBX1_sma_b
#define MBX1_sma_b MBX0_sma_b+MBX0_sml_b
#endif
#ifndef MBX1_sml_b
#define MBX1_sml_b MBXSIZEBOOT
#endif
#ifndef MBX1_sme_b
#define MBX1_sme_b MBX1_sma_b+MBX1_sml_b-1
#endif
#ifndef MBX1_smc_b
#define MBX1_smc_b 0x22
#endif
#ifndef SM2_sma
#define SM2_sma 0x1100
#endif
#ifndef SM2_smc
#define SM2_smc 0x24
#endif
#ifndef SM2_act
#define SM2_act 1
#endif
#ifndef SM3_sma
#define SM3_sma 0x1180
#endif
#ifndef SM3_smc
#define SM3_smc 0x20
#endif
#ifndef SM3_act
#define SM3_act 1
#endif
/* Max number of dynamically mapped objects in SM2. May be 0 to
disable dynamic processdata. */
#ifndef MAX_MAPPINGS_SM2
#define MAX_MAPPINGS_SM2 16
#endif
/* Max number of dynamically mapped objects in SM3. May be 0 to
disable dynamic processdata. */
#ifndef MAX_MAPPINGS_SM3
#define MAX_MAPPINGS_SM3 16
#endif
/* Max processdata size (outputs). Only used if MAX_MAPPINGS_SM2 is
non-zero. */
#ifndef MAX_RXPDO_SIZE
#define MAX_RXPDO_SIZE 128
#endif
/* Max processdata size (inputs). Only used if MAX_MAPPINGS_SM3 is
non-zero. */
#ifndef MAX_TXPDO_SIZE
#define MAX_TXPDO_SIZE 128
#endif
#endif /* __options__ */