Compare commits
77 Commits
Author | SHA1 | Date |
---|---|---|
ArthurKetels | 342ca8632c | |
ArthurKetels | 2c1b9b2756 | |
ArthurKetels | 4b4cdc2c45 | |
ArthurKetels | d9261e801d | |
Andreas Karlsson | 447d184d7e | |
ArthurKetels | b01ceb9905 | |
ArthurKetels | cbc8f36e87 | |
ArthurKetels | f69b1ab702 | |
Andreas Karlsson | 101ac54a7d | |
ArthurKetels | f938df6bac | |
nakarlsson | bb82fc33d7 | |
Hans-Erik Floryd | 08d480cf82 | |
Andreas Karlsson | 33aa7a3c57 | |
Andreas Karlsson | bae37b9028 | |
Pedram Nimreezi | 953eb07f8a | |
berkaydeniz | 63d699d303 | |
Andreas Karlsson | 093311561c | |
seanyen | 7fe05b5b4b | |
Arthur Ketels | 92ff466357 | |
Arthur Ketels | 9ec8635943 | |
Hans-Erik Floryd | 2a8c07c32b | |
Hans-Erik Floryd | f8b0029765 | |
Juanjo Gutiérrez | 7bb27de2a2 | |
Juanjo Gutiérrez | cffd3ba283 | |
Giuseppe Iellamo | 09d48acc32 | |
nakarlsson | abbf0d42e3 | |
ArthurKetels | e2fc362539 | |
Andreas Karlsson | 5c71c281fc | |
Andreas Karlsson | 131158dda8 | |
Andreas Karlsson | 817435066f | |
Andreas Karlsson | cc417d4c0c | |
Andreas Karlsson | 8c1e83ee8e | |
Andreas Karlsson | 9c921d8d4e | |
Andreas Karlsson | 7b1ea32343 | |
Andreas Karlsson | c892921d7e | |
Andreas Karlsson | 49810a5adf | |
Andreas Karlsson | c220255604 | |
Andreas Karlsson | 151045ed56 | |
Andreas Karlsson | b978b4cb5c | |
Marc Butler | 812403783c | |
ArthurKetels | d16d81e51b | |
Vincent Wilms | 4671254849 | |
Schlumpf | 787cf82d7d | |
jopado1 | 537145f6bf | |
Claudio Scordino | 29df9ba013 | |
ArthurKetels | ab89d557d5 | |
andreas karlsson | a37a8c733e | |
nakarlsson | 90065c08d0 | |
ArthurKetels | 5a47e61f24 | |
Andreas Karlsson | aed0f81724 | |
Claudio Scordino | 45e5b4e6eb | |
nakarlsson | 828b8987d9 | |
Andreas Karlsson | 930d6e07c8 | |
ArthurKetels | 8832ef0f2f | |
Claudio Scordino | e0d880d7bd | |
Claudio Scordino | 7beba91c62 | |
Claudio Scordino | 770e4c93d6 | |
Claudio Scordino | 26cde1dc94 | |
Claudio Scordino | 826be99bab | |
nakarlsson | 037a629839 | |
nakarlsson | 86a2584e47 | |
ArthurKetels | 4427684cc5 | |
Qbotics Labs | b4f3a306e4 | |
Schlumpf | 8f2b233837 | |
wanga | 0a67e6bf94 | |
wanga | 2e165bee41 | |
Hans-Erik Floryd | 5b2c51b65c | |
Nikolaos Tsiogkas | 94217505df | |
nakarlsson | b1e4b6ce95 | |
Jesper Smith | d8c5620768 | |
nakarlsson | 0398b6ba72 | |
Zihan Chen | 462464ee37 | |
Zihan Chen | 415131e3f1 | |
nakarlsson | c12de6633a | |
rtlaka | 99f4e1c8f7 | |
nakarlsson | 5261e237e4 | |
rtlaka | 084a3b8576 |
|
@ -3,3 +3,4 @@ install
|
|||
*~
|
||||
/doc/latex
|
||||
/doc/html
|
||||
tags
|
||||
|
|
|
@ -1,3 +1,9 @@
|
|||
jobs:
|
||||
include:
|
||||
- dist: xenial
|
||||
- dist: bionic
|
||||
- os: osx
|
||||
|
||||
language: c
|
||||
|
||||
script:
|
||||
|
|
|
@ -1,26 +1,36 @@
|
|||
cmake_minimum_required(VERSION 2.8.4)
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/Modules")
|
||||
cmake_minimum_required(VERSION 2.8.12)
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake/Modules")
|
||||
project(SOEM C)
|
||||
|
||||
if (CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT)
|
||||
# Default to installing in SOEM source directory
|
||||
set(CMAKE_INSTALL_PREFIX ${CMAKE_SOURCE_DIR}/install)
|
||||
set(CMAKE_INSTALL_PREFIX ${CMAKE_CURRENT_LIST_DIR}/install)
|
||||
endif()
|
||||
|
||||
set(SOEM_INCLUDE_INSTALL_DIR include/soem)
|
||||
set(SOEM_LIB_INSTALL_DIR lib)
|
||||
set(BUILD_TESTS TRUE)
|
||||
|
||||
if(WIN32)
|
||||
set(OS "win32")
|
||||
include_directories(oshw/win32/wpcap/Include)
|
||||
link_directories(${CMAKE_SOURCE_DIR}/oshw/win32/wpcap/Lib)
|
||||
if(CMAKE_SIZEOF_VOID_P EQUAL 8)
|
||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/oshw/win32/wpcap/Lib/x64)
|
||||
elseif(CMAKE_SIZEOF_VOID_P EQUAL 4)
|
||||
link_directories(${CMAKE_CURRENT_LIST_DIR}/oshw/win32/wpcap/Lib)
|
||||
endif()
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /D _CRT_SECURE_NO_WARNINGS")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /WX")
|
||||
set(OS_LIBS wpcap.lib Packet.lib Ws2_32.lib Winmm.lib)
|
||||
elseif(UNIX)
|
||||
elseif(UNIX AND NOT APPLE)
|
||||
set(OS "linux")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra -Werror")
|
||||
set(OS_LIBS pthread rt)
|
||||
elseif(APPLE)
|
||||
# This must come *before* linux or MacOSX will identify as Unix.
|
||||
set(OS "macosx")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra -Werror")
|
||||
set(OS_LIBS pthread pcap)
|
||||
elseif(${CMAKE_SYSTEM_NAME} MATCHES "rt-kernel")
|
||||
set(OS "rtk")
|
||||
message("ARCH is ${ARCH}")
|
||||
|
@ -37,6 +47,7 @@ elseif(${CMAKE_SYSTEM_NAME} MATCHES "rtems")
|
|||
message("Building for RTEMS")
|
||||
set(OS "rtems")
|
||||
set(SOEM_LIB_INSTALL_DIR ${LIB_DIR})
|
||||
set(BUILD_TESTS FALSE)
|
||||
endif()
|
||||
|
||||
message("OS is ${OS}")
|
||||
|
@ -49,11 +60,6 @@ file(GLOB SOEM_HEADERS soem/*.h)
|
|||
file(GLOB OSAL_HEADERS osal/osal.h osal/${OS}/*.h)
|
||||
file(GLOB OSHW_HEADERS oshw/${OS}/*.h)
|
||||
|
||||
include_directories(soem)
|
||||
include_directories(osal)
|
||||
include_directories(osal/${OS})
|
||||
include_directories(oshw/${OS})
|
||||
|
||||
add_library(soem STATIC
|
||||
${SOEM_SOURCES}
|
||||
${OSAL_SOURCES}
|
||||
|
@ -61,15 +67,37 @@ add_library(soem STATIC
|
|||
${OSHW_EXTRA_SOURCES})
|
||||
target_link_libraries(soem ${OS_LIBS})
|
||||
|
||||
target_include_directories(soem PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/soem>
|
||||
$<INSTALL_INTERFACE:include/soem>)
|
||||
|
||||
target_include_directories(soem PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/osal>
|
||||
$<INSTALL_INTERFACE:include/soem>)
|
||||
|
||||
target_include_directories(soem PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/osal/${OS}>
|
||||
$<INSTALL_INTERFACE:include/soem>)
|
||||
|
||||
target_include_directories(soem
|
||||
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/oshw/${OS}>
|
||||
$<INSTALL_INTERFACE:include/soem>
|
||||
)
|
||||
|
||||
message("LIB_DIR: ${SOEM_LIB_INSTALL_DIR}")
|
||||
|
||||
install(TARGETS soem DESTINATION ${SOEM_LIB_INSTALL_DIR})
|
||||
install(TARGETS soem EXPORT soemConfig DESTINATION ${SOEM_LIB_INSTALL_DIR})
|
||||
|
||||
install(EXPORT soemConfig DESTINATION share/soem/cmake)
|
||||
|
||||
install(FILES
|
||||
${SOEM_HEADERS}
|
||||
${OSAL_HEADERS}
|
||||
${OSHW_HEADERS}
|
||||
DESTINATION ${SOEM_INCLUDE_INSTALL_DIR})
|
||||
|
||||
add_subdirectory(test/linux/slaveinfo)
|
||||
add_subdirectory(test/linux/eepromtool)
|
||||
add_subdirectory(test/linux/simple_test)
|
||||
if(BUILD_TESTS)
|
||||
add_subdirectory(test/linux/slaveinfo)
|
||||
add_subdirectory(test/linux/eepromtool)
|
||||
add_subdirectory(test/linux/simple_test)
|
||||
endif()
|
||||
|
|
|
@ -82,4 +82,10 @@ Version 1.3.1 : 2015-03-11
|
|||
- Added intime target.
|
||||
- Added rtk\fec target.
|
||||
- Compiles under gcc / visual-c / borland-c / intime.
|
||||
- Added multi-threaded configuration for parallel configurations of slaves
|
||||
- Added multi-threaded configuration for parallel configurations of slaves
|
||||
Version 1.3.2 : 2018-02-02
|
||||
- Made a mistake. DON'T USE!
|
||||
Version 1.3.3 : 2018-02-02
|
||||
- Added rtems target.
|
||||
- Added support for overlapping IOmap.
|
||||
|
||||
|
|
2
Doxyfile
2
Doxyfile
|
@ -32,7 +32,7 @@ PROJECT_NAME = SOEM
|
|||
# This could be handy for archiving the generated documentation or
|
||||
# if some version control system is used.
|
||||
|
||||
PROJECT_NUMBER = v1.3.1
|
||||
PROJECT_NUMBER = v1.4.0
|
||||
|
||||
# Using the PROJECT_BRIEF tag one can provide an optional one line description
|
||||
# for a project that appears at the top of each page and should give viewer
|
||||
|
|
15
README.md
15
README.md
|
@ -21,14 +21,25 @@ Windows (Visual Studio)
|
|||
* `cmake .. -G "NMake Makefiles"`
|
||||
* `nmake`
|
||||
|
||||
Linux
|
||||
-----
|
||||
Linux & macOS
|
||||
--------------
|
||||
|
||||
* `mkdir build`
|
||||
* `cd build`
|
||||
* `cmake ..`
|
||||
* `make`
|
||||
|
||||
ERIKA Enterprise RTOS
|
||||
---------------------
|
||||
|
||||
* Refer to http://www.erika-enterprise.com/wiki/index.php?title=EtherCAT_Master
|
||||
|
||||
Documentation
|
||||
-------------
|
||||
|
||||
See https://openethercatsociety.github.io/doc/soem/
|
||||
|
||||
|
||||
Want to contribute to SOEM or SOES?
|
||||
-----------------------------------
|
||||
|
||||
|
|
Binary file not shown.
After Width: | Height: | Size: 24 KiB |
Binary file not shown.
After Width: | Height: | Size: 28 KiB |
66
doc/soem.dox
66
doc/soem.dox
|
@ -1,7 +1,7 @@
|
|||
/**
|
||||
* \mainpage Simple Open EtherCAT Master or SOEM
|
||||
*
|
||||
* \section start Tutorial
|
||||
* \section tutorial Tutorial
|
||||
* For a tutorial on SOEM See tutorial.txt
|
||||
*
|
||||
* \section overview Overview
|
||||
|
@ -10,11 +10,11 @@
|
|||
* how an EtherCAT master functions and how it interacts with EtherCAT slaves.
|
||||
*
|
||||
* As all applications are different SOEM tries to not impose any design architecture.
|
||||
* Under Linux it can be used in generic user mode, PREEMPT_RT or Xenomai. under Windows
|
||||
* Under Linux it can be used in generic user mode, PREEMPT_RT or Xenomai. Under Windows
|
||||
* it can be used as user mode program.
|
||||
*
|
||||
* Preconditions Linux:
|
||||
* - Linux 2.6 kernel.
|
||||
* - Linux 2.6 kernel or later.
|
||||
* - GCC compiler (others might work, just not tested).
|
||||
* - One (or two if in redundant mode) 100Mb/s NIC that can connect to a RAW socket.
|
||||
* - Application must run as root / kernel.
|
||||
|
@ -45,7 +45,7 @@
|
|||
* - Distributed Clock (DC) support.
|
||||
* - Automatic configuration of DC slaves.
|
||||
* - Automatic sync of clocks with process data exchange.
|
||||
* - Flexible settting of sync0 and sync1 firing per slave.
|
||||
* - Flexible setting of sync0 and sync1 firing per slave.
|
||||
* - Access to slave functions through one slave structure.
|
||||
* - EEPROM read / write.
|
||||
* - Local cache for EEPROM access with automatic 4/8 byte reading.
|
||||
|
@ -63,7 +63,7 @@
|
|||
* - SYNC1 generation supported.
|
||||
*
|
||||
* Features as of 1.2.0 :
|
||||
* - Changed license to GPLv2 only. Adresses leagal concerns about master licensing.
|
||||
* - Changed license to GPLv2 only. Addresses legal concerns about master licensing.
|
||||
* - Slave init and process data mapping is split in two functions. This allows
|
||||
* dynamic user reconfiguration of PDO mapping.
|
||||
* - Eeprom transfer to and from PDI
|
||||
|
@ -93,7 +93,7 @@
|
|||
* Features as of 1.2.8 :
|
||||
* - Changed directory structure.
|
||||
* - Changed make file.
|
||||
* - Moved hardware / OS dependend part in separate directories.
|
||||
* - Moved hardware / OS dependent part in separate directories.
|
||||
* - Added firm_update tool to upload firmware to slaves in Boot state, use with care.
|
||||
* - Added DC for LRD/LWR case.
|
||||
* - Separated expectedWKC to inputsWKC and outputsWKC.
|
||||
|
@ -114,6 +114,13 @@
|
|||
* - Error messages updated to latest ETG1020 document.
|
||||
* - FoE transfers now support busy response.
|
||||
*
|
||||
* Features as of 1.4.0 :
|
||||
*
|
||||
* Added ERIKA target.
|
||||
* Added macOS target.
|
||||
* Support for EoE over existing mailbox API.
|
||||
*
|
||||
*
|
||||
* \section build Build instructions
|
||||
*
|
||||
* See README.md in the root folder.
|
||||
|
@ -176,42 +183,23 @@
|
|||
*
|
||||
* Version 1.3.1
|
||||
* - Added intime target.
|
||||
* - Added rtk\fec target.
|
||||
* - Added rtk fec target.
|
||||
* - Compiles under gcc / visual-c / intime / borland-c .
|
||||
* - Added multi-threaded configuration for parallel configurations of slaves
|
||||
*
|
||||
* Version 1.3.2 : 2018-02-02
|
||||
* - Made a mistake. DON'T USE!
|
||||
*
|
||||
* Version 1.3.3 : 2018-02-02
|
||||
* - Added rtems target.
|
||||
* - Added support for overlapping IOmap.
|
||||
*
|
||||
* Version 1.4.0 : 2019-05
|
||||
* - Various fixes and improvements
|
||||
*
|
||||
* \section legal Legal notice
|
||||
* Copyright© 2005-2015 Speciaal Machinefabriek Ketels v.o.f. \n
|
||||
* Copyright© 2005-2015 Arthur Ketels \n
|
||||
* Copyright© 2008-2010 TU/e Technische Universiteit Eindhoven \n
|
||||
* Copyright© 2012-2015 RT-labs AB \n
|
||||
*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*
|
||||
* SOEM 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.
|
||||
*
|
||||
* SOEM 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. You can use SOEM for
|
||||
* the sole purpose of creating, using and/or selling or otherwise distributing
|
||||
* an EtherCAT network master provided that an EtherCAT Master License is obtained
|
||||
* from Beckhoff Automation GmbH.
|
||||
*
|
||||
* In case you did not receive a copy of the EtherCAT Master License along with
|
||||
* SOEM write to Beckhoff Automation GmbH, Eiserstrasse 5, D-33415 Verl, Germany
|
||||
* (www.beckhoff.com).
|
||||
*/
|
||||
|
|
143
doc/tutorial.txt
143
doc/tutorial.txt
|
@ -5,7 +5,7 @@
|
|||
The SOEM is a library that provides the user application with the means to send
|
||||
and receive EtherCAT frames. It is up to the application to provide means for:
|
||||
- Reading and writing process data to be sent/received by SOEM
|
||||
- Keeping local IO data synchronised with the global IOmap
|
||||
- Keeping local IO data synchronized with the global IOmap
|
||||
- Detecting errors reported by SOEM
|
||||
- Managing errors reported by SOEM
|
||||
|
||||
|
@ -150,9 +150,128 @@ handling is split into ec_send_processdata and ec_receive_processdata.
|
|||
|
||||
- Now we have a system up and running, all slaves are in state operational.
|
||||
|
||||
\section configuration_custom Custom Configuration
|
||||
|
||||
\subsection iomap_config PDO Assign and PDO Config
|
||||
|
||||
Do custom configuration with PDO Assign or PDO Config. SOEM support custom configuration during start via a
|
||||
PreOP to SafeOP configuration hook. It can be done per slave and should be set before calling
|
||||
the configuration and mapping of process data, e.g. the call to ec_config_map. Setting the configuration
|
||||
hook ensure that the custom configuration will be applied when calling recover and re-configuration
|
||||
of a slave, as described below.
|
||||
|
||||
\code
|
||||
|
||||
int EL7031setup(uint16 slave)
|
||||
{
|
||||
int retval;
|
||||
uint16 u16val;
|
||||
|
||||
retval = 0;
|
||||
|
||||
/* Map velocity PDO assignment via Complete Access*/
|
||||
uint16 map_1c12[4] = {0x0003, 0x1601, 0x1602, 0x1604};
|
||||
uint16 map_1c13[3] = {0x0002, 0x1a01, 0x1a03};
|
||||
|
||||
retval += ec_SDOwrite(slave, 0x1c12, 0x00, TRUE, sizeof(map_1c12), &map_1c12, EC_TIMEOUTSAFE);
|
||||
retval += ec_SDOwrite(slave, 0x1c13, 0x00, TRUE, sizeof(map_1c13), &map_1c13, EC_TIMEOUTSAFE);
|
||||
|
||||
/* set some motor parameters, just as example */
|
||||
u16val = 1200; // max motor current in mA
|
||||
retval += ec_SDOwrite(slave, 0x8010, 0x01, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTSAFE);
|
||||
u16val = 150; // motor coil resistance in 0.01ohm
|
||||
retval += ec_SDOwrite(slave, 0x8010, 0x04, FALSE, sizeof(u16val), &u16val, EC_TIMEOUTSAFE);
|
||||
|
||||
/* set other necessary parameters as needed */
|
||||
...
|
||||
printf("EL7031 slave %d set, retval = %d\n", slave, retval);
|
||||
return 1;
|
||||
}
|
||||
|
||||
void simpletest(char *ifname)
|
||||
{
|
||||
...
|
||||
/* Detect slave beckhoff EL7031 from vendor ID and product code */
|
||||
if((ec_slave[slc].eep_man == 0x00000002) && (ec_slave[slc].eep_id == 0x1b773052))
|
||||
{
|
||||
printf("Found %s at position %d\n", ec_slave[slc].name, slc);
|
||||
/* link slave specific setup to preop->safeop hook */
|
||||
ec_slave[slc].PO2SOconfig = EL7031setup;
|
||||
}
|
||||
...
|
||||
\endcode
|
||||
|
||||
\subsection iomap_layout Legacy versus overlapping IOmap
|
||||
|
||||
IOmap options legacy versus overlapping. Overlapping IOmap was introduced to handle
|
||||
the TI ESC that doesn't support RW access to non-interleaved input and output process
|
||||
data of multiple slaves. The difference is that legacy IOmapping will send IOmap as is
|
||||
on the EtherCAT network while the overlapping will re-use logic addressing per slave to
|
||||
replace RxPDO process data coming from the Master with TxPDO process data generated by the slave
|
||||
sent back to the master.
|
||||
|
||||
Overview of legacy pdo map
|
||||
\image html legacy_iomap.png "Legacy IOmapping"
|
||||
\image latex legacy_iomap.png "Legacy IOmapping" width=15cm
|
||||
|
||||
Overview of overlapping pdo map
|
||||
\image html overlapping_iomap.png "Overlapping IOmapping"
|
||||
\image latex overlapping_iomap.png "Overlapping IOmapping" width=15cm
|
||||
|
||||
\subsection iomap_groups EtherCAT slave groups
|
||||
|
||||
Slave groups can be used to group slaves into separate logic groups within an EtherCAT network.
|
||||
Each group will have its own logic address space mapped to an IOmap address and make it possible to
|
||||
send and receive process data at different update rate.
|
||||
|
||||
Below is an example on how to assign a slave to a group. <b>OBS!</b> A slave can only be member in one group.
|
||||
|
||||
\code
|
||||
for (cnt = 1; cnt <= ec_slavecount; cnt++)
|
||||
{
|
||||
if ( <some condition> )
|
||||
{
|
||||
ec_slave[cnt].group = X;
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_slave[cnt].group = Y;
|
||||
}
|
||||
}
|
||||
\endcode
|
||||
|
||||
Alternative 1, configure all slave groups at once, call ec_config_map or ec_config_map_group with arg 0.
|
||||
This option will share IOmap and store the group IOmap data at offset EC_LOGGROUPOFFSET.
|
||||
|
||||
\code
|
||||
ec_config_map_group(&IOmap, 0);
|
||||
\endcode
|
||||
|
||||
Alternative 2, configure the slave groups one by one, call ec_config_map or ec_config_map_group with arg X, Y.
|
||||
This option will use different, supplied by the user, IOmaps.
|
||||
|
||||
\code
|
||||
ec_config_map_group(&IOmap1, X);
|
||||
ec_config_map_group(&IOmap2, Y);
|
||||
\endcode
|
||||
|
||||
To exchange process data for given group(s) the user must call send/recv process data per group.
|
||||
The send and receive stack of process data don't consider groups, so the application has to send
|
||||
and receive the process data for one group before sending/receiving process data for another group.
|
||||
|
||||
\code
|
||||
ec_send_processdata_group(X);
|
||||
ec_receive_processdata_group(X, EC_TIMEOUTRET);
|
||||
ec_send_processdata_group(Y);
|
||||
ec_receive_processdata_group(Y, EC_TIMEOUTRET);
|
||||
\endcode
|
||||
|
||||
\section application Application
|
||||
|
||||
IO data is accessed through the IOmap, the ec_slave struct keep pointers
|
||||
\subsection iomap Accessing data through IOmap
|
||||
|
||||
IOmap is the fastest mechanism for accessing slaves' IO data.
|
||||
Using this mechanism, the ec_slave struct keeps pointers
|
||||
to the start byte in the IO map on slave level together with start bit within
|
||||
the start byte. This way we can bit mask IO on bit level even though SOEM
|
||||
has combined slave data to minimize the frame size to be sent. We'll use
|
||||
|
@ -300,7 +419,27 @@ if( inOP && ((wkc < expectedWKC) || ec_group[currentgroup].docheckstate))
|
|||
printf("OK : all slaves resumed OPERATIONAL.\n");
|
||||
}
|
||||
\endcode
|
||||
|
||||
|
||||
\subsection sdo Accessing SDOs and PDOs
|
||||
|
||||
There are multiple ways a slave can communicate with the master. CANopen over
|
||||
EtherCAT (CoE) is a (slow but flexible) asynchronous mechanism for transferring
|
||||
data via mailboxes.
|
||||
|
||||
SOEM provides the ecx_SDOread() and ecx_SDOwrite() functions for reading and
|
||||
writing a CoE SDO (Service Data Object) given the corresponding index and
|
||||
subindex.
|
||||
|
||||
SOEM does not provide specific functions for accessing CoE PDOs (Process Data
|
||||
Objects). On most slaves, however, it is possible to use the same functions
|
||||
available for SDOs. In the seldom case in which the PDO object has been marked
|
||||
in the CoE dictionary as "PDO only", only IOmap access is allowed.
|
||||
Note that a list of the PDO mappings can be retrieved through the "slaveinfo
|
||||
<interface> -map" command.
|
||||
|
||||
---------------------
|
||||
|
||||
This tutorial is just one way of doing it.
|
||||
Enjoy and happy coding!
|
||||
|
||||
|
|
|
@ -0,0 +1,103 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#include <time.h>
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <osal.h>
|
||||
|
||||
#include "ee_x86_64_tsc.h"
|
||||
|
||||
#define USECS_PER_SEC 1000000
|
||||
#define NSECS_PER_SEC 1000000000
|
||||
|
||||
uint64_t osEE_x86_64_tsc_read(void);
|
||||
|
||||
void ee_usleep(uint32 usec);
|
||||
|
||||
inline int osal_usleep (uint32 usec)
|
||||
{
|
||||
ee_usleep(usec);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
uint64_t time = osEE_x86_64_tsc_read();
|
||||
tv->tv_sec = time/NSECS_PER_SEC;
|
||||
tv->tv_sec += 946684800UL; /* EtherCAT uses 2000-01-01 as epoch start */
|
||||
tv->tv_usec = (time%NSECS_PER_SEC)/1000;
|
||||
return 0;
|
||||
}
|
||||
|
||||
ec_timet osal_current_time(void)
|
||||
{
|
||||
struct timeval current_time;
|
||||
ec_timet ret;
|
||||
|
||||
osal_gettimeofday(¤t_time, 0);
|
||||
ret.sec = current_time.tv_sec;
|
||||
ret.usec = current_time.tv_usec;
|
||||
return ret;
|
||||
}
|
||||
|
||||
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
|
||||
{
|
||||
if (end->usec < start->usec) {
|
||||
diff->sec = end->sec - start->sec - 1;
|
||||
diff->usec = end->usec + USECS_PER_SEC - start->usec;
|
||||
} else {
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
}
|
||||
}
|
||||
|
||||
void osal_timer_start(osal_timert *self, uint32 timeout_usec)
|
||||
{
|
||||
struct timeval start_time;
|
||||
struct timeval timeout;
|
||||
struct timeval stop_time;
|
||||
|
||||
osal_gettimeofday(&start_time, 0);
|
||||
timeout.tv_sec = timeout_usec / USECS_PER_SEC;
|
||||
timeout.tv_usec = timeout_usec % USECS_PER_SEC;
|
||||
timeradd(&start_time, &timeout, &stop_time);
|
||||
|
||||
self->stop_time.sec = stop_time.tv_sec;
|
||||
self->stop_time.usec = stop_time.tv_usec;
|
||||
}
|
||||
|
||||
boolean osal_timer_is_expired (osal_timert *self)
|
||||
{
|
||||
struct timeval current_time;
|
||||
struct timeval stop_time;
|
||||
int is_not_yet_expired;
|
||||
|
||||
osal_gettimeofday (¤t_time, 0);
|
||||
stop_time.tv_sec = self->stop_time.sec;
|
||||
stop_time.tv_usec = self->stop_time.usec;
|
||||
is_not_yet_expired = timercmp (¤t_time, &stop_time, <);
|
||||
/* OSEE_PRINT("current: %d:%d -- expire: %d:%d -- result: %d\n", */
|
||||
/* current_time.tv_sec, */
|
||||
/* current_time.tv_usec, */
|
||||
/* stop_time.tv_sec, */
|
||||
/* stop_time.tv_usec, */
|
||||
/* is_not_yet_expired); */
|
||||
|
||||
return is_not_yet_expired == FALSE;
|
||||
}
|
||||
|
||||
void *osal_malloc(size_t size)
|
||||
{
|
||||
return malloc(size);
|
||||
}
|
||||
|
||||
void osal_free(void *ptr)
|
||||
{
|
||||
free(ptr);
|
||||
}
|
||||
|
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#ifndef _osal_defs_
|
||||
#define _osal_defs_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <sys/time.h>
|
||||
#include <stdlib.h>
|
||||
#include <ee.h>
|
||||
|
||||
// define if debug print is needed
|
||||
#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT OSEE_PRINT
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
#define PACKED_END
|
||||
#endif
|
||||
|
||||
int osal_gettimeofday(struct timeval *tv, struct timezone *tz);
|
||||
void *osal_malloc(size_t size);
|
||||
void osal_free(void *ptr);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -11,6 +11,15 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#ifdef _MSC_VER
|
||||
#define PACKED_BEGIN __pragma(pack(push, 1))
|
||||
|
|
|
@ -17,7 +17,7 @@ int osal_usleep (uint32 usec)
|
|||
struct timespec ts;
|
||||
ts.tv_sec = usec / USECS_PER_SEC;
|
||||
ts.tv_nsec = (usec % USECS_PER_SEC) * 1000;
|
||||
/* usleep is depricated, use nanosleep instead */
|
||||
/* usleep is deprecated, use nanosleep instead */
|
||||
return nanosleep(&ts, NULL);
|
||||
}
|
||||
|
||||
|
|
|
@ -11,6 +11,15 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
|
|
|
@ -0,0 +1,144 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#include <time.h>
|
||||
#include <sys/time.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <osal.h>
|
||||
|
||||
#define USECS_PER_SEC 1000000
|
||||
|
||||
int osal_usleep (uint32 usec)
|
||||
{
|
||||
struct timespec ts;
|
||||
ts.tv_sec = usec / USECS_PER_SEC;
|
||||
ts.tv_nsec = (usec % USECS_PER_SEC) * 1000;
|
||||
/* usleep is deprecated, use nanosleep instead */
|
||||
return nanosleep(&ts, NULL);
|
||||
}
|
||||
|
||||
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
struct timespec ts;
|
||||
int return_value;
|
||||
(void)tz; /* Not used */
|
||||
|
||||
/* Use clock_gettime to prevent possible live-lock.
|
||||
* Gettimeofday uses CLOCK_REALTIME that can get NTP timeadjust.
|
||||
* If this function preempts timeadjust and it uses vpage it live-locks.
|
||||
* Also when using XENOMAI, only clock_gettime is RT safe */
|
||||
return_value = clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
tv->tv_sec = ts.tv_sec;
|
||||
tv->tv_usec = ts.tv_nsec / 1000;
|
||||
return return_value;
|
||||
}
|
||||
|
||||
ec_timet osal_current_time(void)
|
||||
{
|
||||
struct timeval current_time;
|
||||
ec_timet return_value;
|
||||
|
||||
osal_gettimeofday(¤t_time, 0);
|
||||
return_value.sec = current_time.tv_sec;
|
||||
return_value.usec = current_time.tv_usec;
|
||||
return return_value;
|
||||
}
|
||||
|
||||
void osal_time_diff(ec_timet *start, ec_timet *end, ec_timet *diff)
|
||||
{
|
||||
if (end->usec < start->usec) {
|
||||
diff->sec = end->sec - start->sec - 1;
|
||||
diff->usec = end->usec + 1000000 - start->usec;
|
||||
}
|
||||
else {
|
||||
diff->sec = end->sec - start->sec;
|
||||
diff->usec = end->usec - start->usec;
|
||||
}
|
||||
}
|
||||
|
||||
void osal_timer_start(osal_timert * self, uint32 timeout_usec)
|
||||
{
|
||||
struct timeval start_time;
|
||||
struct timeval timeout;
|
||||
struct timeval stop_time;
|
||||
|
||||
osal_gettimeofday(&start_time, 0);
|
||||
timeout.tv_sec = timeout_usec / USECS_PER_SEC;
|
||||
timeout.tv_usec = timeout_usec % USECS_PER_SEC;
|
||||
timeradd(&start_time, &timeout, &stop_time);
|
||||
|
||||
self->stop_time.sec = stop_time.tv_sec;
|
||||
self->stop_time.usec = stop_time.tv_usec;
|
||||
}
|
||||
|
||||
boolean osal_timer_is_expired (osal_timert * self)
|
||||
{
|
||||
struct timeval current_time;
|
||||
struct timeval stop_time;
|
||||
int is_not_yet_expired;
|
||||
|
||||
osal_gettimeofday(¤t_time, 0);
|
||||
stop_time.tv_sec = self->stop_time.sec;
|
||||
stop_time.tv_usec = self->stop_time.usec;
|
||||
is_not_yet_expired = timercmp(¤t_time, &stop_time, <);
|
||||
|
||||
return is_not_yet_expired == FALSE;
|
||||
}
|
||||
|
||||
void *osal_malloc(size_t size)
|
||||
{
|
||||
return malloc(size);
|
||||
}
|
||||
|
||||
void osal_free(void *ptr)
|
||||
{
|
||||
free(ptr);
|
||||
}
|
||||
|
||||
int osal_thread_create(void *thandle, int stacksize, void *func, void *param)
|
||||
{
|
||||
int ret;
|
||||
pthread_attr_t attr;
|
||||
pthread_t *threadp;
|
||||
|
||||
threadp = thandle;
|
||||
pthread_attr_init(&attr);
|
||||
pthread_attr_setstacksize(&attr, stacksize);
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
int osal_thread_create_rt(void *thandle, int stacksize, void *func, void *param)
|
||||
{
|
||||
int ret;
|
||||
pthread_attr_t attr;
|
||||
struct sched_param schparam;
|
||||
pthread_t *threadp;
|
||||
|
||||
threadp = thandle;
|
||||
pthread_attr_init(&attr);
|
||||
pthread_attr_setstacksize(&attr, stacksize);
|
||||
ret = pthread_create(threadp, &attr, func, param);
|
||||
pthread_attr_destroy(&attr);
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
memset(&schparam, 0, sizeof(schparam));
|
||||
schparam.sched_priority = 40;
|
||||
ret = pthread_setschedparam(*threadp, SCHED_FIFO, &schparam);
|
||||
if(ret < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
|
@ -0,0 +1,38 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#ifndef _osal_defs_
|
||||
#define _osal_defs_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
#define PACKED_END
|
||||
#endif
|
||||
|
||||
#include <pthread.h>
|
||||
#define OSAL_THREAD_HANDLE pthread_t *
|
||||
#define OSAL_THREAD_FUNC void
|
||||
#define OSAL_THREAD_FUNC_RT void
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -15,9 +15,13 @@ extern "C"
|
|||
#include <stdint.h>
|
||||
|
||||
/* General types */
|
||||
typedef uint8_t boolean;
|
||||
#ifndef TRUE
|
||||
#define TRUE 1
|
||||
#endif
|
||||
#ifndef FALSE
|
||||
#define FALSE 0
|
||||
#endif
|
||||
typedef uint8_t boolean;
|
||||
typedef int8_t int8;
|
||||
typedef int16_t int16;
|
||||
typedef int32_t int32;
|
||||
|
|
|
@ -17,7 +17,7 @@ int osal_usleep (uint32 usec)
|
|||
struct timespec ts;
|
||||
ts.tv_sec = usec / USECS_PER_SEC;
|
||||
ts.tv_nsec = (usec % USECS_PER_SEC) * 1000;
|
||||
/* usleep is depricated, use nanosleep instead */
|
||||
/* usleep is deprecated, use nanosleep instead */
|
||||
return nanosleep(&ts, NULL);
|
||||
}
|
||||
|
||||
|
|
|
@ -11,6 +11,15 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
|
|
|
@ -11,6 +11,15 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
|
|
|
@ -72,10 +72,14 @@ int osal_usleep (uint32 usec)
|
|||
|
||||
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
struct timespec ts;
|
||||
int return_value;
|
||||
(void)tz; /* Not used */
|
||||
|
||||
return_value = gettimeofday(tv, tz);
|
||||
|
||||
/* Use clock_gettime CLOCK_MONOTONIC to a avoid NTP time adjustments */
|
||||
return_value = clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
tv->tv_sec = ts.tv_sec;
|
||||
tv->tv_usec = ts.tv_nsec / 1000;
|
||||
return return_value;
|
||||
}
|
||||
|
||||
|
|
|
@ -6,6 +6,15 @@
|
|||
#ifndef _osal_defs_
|
||||
#define _osal_defs_
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN
|
||||
#define PACKED __attribute__((__packed__))
|
||||
|
|
|
@ -12,7 +12,7 @@ static double qpc2usec;
|
|||
|
||||
#define USECS_PER_SEC 1000000
|
||||
|
||||
int osal_gettimeofday (struct timeval *tv, struct timezone *tz)
|
||||
int osal_getrelativetime(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
int64_t wintime, usecs;
|
||||
if(!sysfrequency)
|
||||
|
@ -29,6 +29,33 @@ int osal_gettimeofday (struct timeval *tv, struct timezone *tz)
|
|||
return 1;
|
||||
}
|
||||
|
||||
int osal_gettimeofday(struct timeval *tv, struct timezone *tz)
|
||||
{
|
||||
FILETIME system_time;
|
||||
int64 system_time64, usecs;
|
||||
|
||||
/* The offset variable is required to switch from Windows epoch (January 1, 1601) to
|
||||
* Unix epoch (January 1, 1970). Number of days between both epochs: 134.774
|
||||
*
|
||||
* The time returned by GetSystemTimeAsFileTime() changes in 100 ns steps, so the
|
||||
* following factors are required for the conversion from days to 100 ns steps:
|
||||
*
|
||||
* 86.400 seconds per day; 1.000.000 microseconds per second; 10 * 100 ns per microsecond
|
||||
*/
|
||||
int64 offset = -134774LL * 86400LL * 1000000LL * 10LL;
|
||||
|
||||
GetSystemTimeAsFileTime(&system_time);
|
||||
|
||||
system_time64 = ((int64)(system_time.dwHighDateTime) << 32) + (int64)system_time.dwLowDateTime;
|
||||
system_time64 += offset;
|
||||
usecs = system_time64 / 10;
|
||||
|
||||
tv->tv_sec = (long)(usecs / 1000000);
|
||||
tv->tv_usec = (long)(usecs - (tv->tv_sec * 1000000));
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
ec_timet osal_current_time (void)
|
||||
{
|
||||
struct timeval current_time;
|
||||
|
@ -58,7 +85,7 @@ void osal_timer_start (osal_timert *self, uint32 timeout_usec)
|
|||
struct timeval timeout;
|
||||
struct timeval stop_time;
|
||||
|
||||
osal_gettimeofday (&start_time, 0);
|
||||
osal_getrelativetime (&start_time, 0);
|
||||
timeout.tv_sec = timeout_usec / USECS_PER_SEC;
|
||||
timeout.tv_usec = timeout_usec % USECS_PER_SEC;
|
||||
timeradd (&start_time, &timeout, &stop_time);
|
||||
|
@ -73,7 +100,7 @@ boolean osal_timer_is_expired (osal_timert *self)
|
|||
struct timeval stop_time;
|
||||
int is_not_yet_expired;
|
||||
|
||||
osal_gettimeofday (¤t_time, 0);
|
||||
osal_getrelativetime (¤t_time, 0);
|
||||
stop_time.tv_sec = self->stop_time.sec;
|
||||
stop_time.tv_usec = self->stop_time.usec;
|
||||
is_not_yet_expired = timercmp (¤t_time, &stop_time, <);
|
||||
|
|
|
@ -11,6 +11,15 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
#ifndef PACKED
|
||||
#define PACKED_BEGIN __pragma(pack(push, 1))
|
||||
#define PACKED
|
||||
|
|
|
@ -0,0 +1,561 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* EtherCAT RAW socket driver.
|
||||
*
|
||||
* Low level interface functions to send and receive EtherCAT packets.
|
||||
* EtherCAT has the property that packets are only send by the master,
|
||||
* and the send packets always return in the receive buffer.
|
||||
* There can be multiple packets "on the wire" before they return.
|
||||
* To combine the received packets with the original send packets a buffer
|
||||
* system is installed. The identifier is put in the index item of the
|
||||
* EtherCAT header. The index is stored and compared when a frame is received.
|
||||
* If there is a match the packet can be combined with the transmit packet
|
||||
* and returned to the higher level function.
|
||||
*
|
||||
* The socket layer can exhibit a reversal in the packet order (rare).
|
||||
* If the Tx order is A-B-C the return order could be A-C-B. The indexed buffer
|
||||
* will reorder the packets automatically.
|
||||
*
|
||||
* The "redundant" option will configure two sockets and two NIC interfaces.
|
||||
* Slaves are connected to both interfaces, one on the IN port and one on the
|
||||
* OUT port. Packets are send via both interfaces. Any one of the connections
|
||||
* (also an interconnect) can be removed and the slaves are still serviced with
|
||||
* packets. The software layer will detect the possible failure modes and
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer if fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <sys/types.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
|
||||
#include "oshw.h"
|
||||
#include "osal.h"
|
||||
#include "nicdrv.h"
|
||||
#include "ee.h"
|
||||
#include "intel_i210.h"
|
||||
#include "ee_x86_64_tsc.h"
|
||||
|
||||
/** Redundancy modes */
|
||||
enum
|
||||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
||||
/** Primary source MAC address used for EtherCAT.
|
||||
* This address is not the MAC address used from the NIC.
|
||||
* EtherCAT does not care about MAC addressing, but it is used here to
|
||||
* differentiate the route the packet traverses through the EtherCAT
|
||||
* segment. This is needed to find out the packet flow in redundant
|
||||
* configurations. */
|
||||
const uint16 priMAC[3] = { 0x0201, 0x0101, 0x0101 };
|
||||
/** Secondary source MAC address used for EtherCAT. */
|
||||
const uint16 secMAC[3] = { 0x0604, 0x0404, 0x0404 };
|
||||
|
||||
/** second MAC word is used for identification */
|
||||
#define RX_PRIM priMAC[1]
|
||||
/** second MAC word is used for identification */
|
||||
#define RX_SEC secMAC[1]
|
||||
|
||||
void ee_port_lock(void);
|
||||
void ee_port_unlock(void);
|
||||
|
||||
static inline void ecx_clear_rxbufstat(int *rxbufstat)
|
||||
{
|
||||
int i;
|
||||
for(i = 0; i < EC_MAXBUF; i++)
|
||||
rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
/** Basic setup to connect NIC to socket.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] ifname = Name of NIC device, f.e. "eth0"
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
int d;
|
||||
struct eth_device *dev;
|
||||
OSEE_PRINT("ecx_setupnic() searching %s...\n", ifname);
|
||||
|
||||
for (d = 0;; ++d) {
|
||||
dev = eth_get_device(d);
|
||||
|
||||
if (dev == NULL)
|
||||
break; // ERROR: device not found
|
||||
|
||||
if (!strncmp(dev->name, ifname, MAX_DEVICE_NAME)){
|
||||
// Device found
|
||||
int i;
|
||||
|
||||
eth_setup_device(d, 1, 100);
|
||||
port->dev_id = d;
|
||||
|
||||
port->sockhandle = -1;
|
||||
port->lastidx = 0;
|
||||
port->redstate = ECT_RED_NONE;
|
||||
port->stack.sock = &(port->sockhandle);
|
||||
port->stack.txbuf = &(port->txbuf);
|
||||
port->stack.txbuflength = &(port->txbuflength);
|
||||
port->stack.tempbuf = &(port->tempinbuf);
|
||||
port->stack.rxbuf = &(port->rxbuf);
|
||||
port->stack.rxbufstat = &(port->rxbufstat);
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
ec_setupheader(&(port->txbuf[i]));
|
||||
port->rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
ec_setupheader(&(port->txbuf2));
|
||||
|
||||
break; // device found
|
||||
}
|
||||
}
|
||||
|
||||
return (dev != NULL);
|
||||
}
|
||||
|
||||
/** Close sockets used
|
||||
* @param[in] port = port context struct
|
||||
* @return 0
|
||||
*/
|
||||
inline int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
// Nothing to do
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
{
|
||||
ec_etherheadert *bp;
|
||||
bp = p;
|
||||
bp->da0 = oshw_htons(0xffff);
|
||||
bp->da1 = oshw_htons(0xffff);
|
||||
bp->da2 = oshw_htons(0xffff);
|
||||
bp->sa0 = oshw_htons(priMAC[0]);
|
||||
bp->sa1 = oshw_htons(priMAC[1]);
|
||||
bp->sa2 = oshw_htons(priMAC[2]);
|
||||
bp->etype = oshw_htons(ETH_P_ECAT);
|
||||
}
|
||||
|
||||
/** Get new frame identifier index and allocate corresponding rx buffer.
|
||||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
uint8 idx;
|
||||
uint8 cnt = 0;
|
||||
|
||||
ee_port_lock();
|
||||
|
||||
idx = port->lastidx + 1;
|
||||
/* index can't be larger than buffer array */
|
||||
if (idx >= EC_MAXBUF)
|
||||
idx = 0;
|
||||
|
||||
/* try to find unused index */
|
||||
while ((port->rxbufstat[idx] != EC_BUF_EMPTY) && (cnt < EC_MAXBUF)) {
|
||||
idx++;
|
||||
cnt++;
|
||||
if (idx >= EC_MAXBUF)
|
||||
idx = 0;
|
||||
}
|
||||
port->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
port->lastidx = idx;
|
||||
|
||||
ee_port_unlock();
|
||||
|
||||
return idx;
|
||||
}
|
||||
|
||||
/** Set rx buffer status.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
port->redport->rxbufstat[idx] = bufstat;
|
||||
}
|
||||
|
||||
/** Transmit buffer over socket (non blocking).
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in tx buffer array
|
||||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp;
|
||||
ec_stackT *stack;
|
||||
|
||||
if (!stacknumber)
|
||||
stack = &(port->stack);
|
||||
else
|
||||
stack = &(port->redport->stack);
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
|
||||
eth_send_packet(port->dev_id, (*stack->txbuf)[idx], lp, 1);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/** Transmit buffer over socket (non blocking).
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
int rval;
|
||||
|
||||
ehp = (ec_etherheadert *)&(port->txbuf[idx]);
|
||||
/* rewrite MAC source address 1 to primary */
|
||||
ehp->sa1 = oshw_htons(priMAC[1]);
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE) {
|
||||
ee_port_lock();
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
datagramP = (ec_comt*)&(port->txbuf2[ETH_HEADERSIZE]);
|
||||
/* write index to frame */
|
||||
datagramP->index = idx;
|
||||
/* rewrite MAC source address 1 to secondary */
|
||||
ehp->sa1 = oshw_htons(secMAC[1]);
|
||||
/* transmit over secondary socket */
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
eth_send_packet(port->dev_id, &(port->txbuf2), port->txbuflength2, 1);
|
||||
ee_port_unlock();
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
/** Non blocking read of socket. Put frame in temporary buffer.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
* @return >0 if frame is available and read
|
||||
*/
|
||||
static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
{
|
||||
int lp, bytesrx;
|
||||
ec_stackT *stack;
|
||||
|
||||
if (!stacknumber)
|
||||
stack = &(port->stack);
|
||||
else
|
||||
stack = &(port->redport->stack);
|
||||
lp = sizeof(port->tempinbuf);
|
||||
bytesrx = eth_receive_packet(port->dev_id, (*stack->tempbuf), lp, 1, 0);
|
||||
port->tempinbufs = bytesrx;
|
||||
|
||||
return (bytesrx > 0);
|
||||
}
|
||||
|
||||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
* than requested index, store in buffer and exit. 3 frame read with matching
|
||||
* index, store in buffer, set completed flag in buffer status and exit.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
uint8 idxf;
|
||||
ec_etherheadert *ehp;
|
||||
ec_comt *ecp;
|
||||
ec_stackT *stack;
|
||||
ec_bufT *rxbuf;
|
||||
|
||||
if (!stacknumber)
|
||||
stack = &(port->stack);
|
||||
else
|
||||
stack = &(port->redport->stack);
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD)) {
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
rval = ((*rxbuf)[l] + ((uint16)(*rxbuf)[l + 1] << 8));
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
} else {
|
||||
ee_port_lock();
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
|
||||
|
||||
while (1) {
|
||||
if (ecx_recvpkt(port, stacknumber)) {
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp =(ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == oshw_htons(ETH_P_ECAT)) {
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx) {
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
/* return WKC */
|
||||
rval = ((*rxbuf)[l] + ((uint16)((*rxbuf)[l + 1]) << 8));
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = oshw_ntohs(ehp->sa1);
|
||||
break;
|
||||
} else if (idxf < EC_MAXBUF && (*stack->rxbufstat)[idxf] == EC_BUF_TX) {
|
||||
rxbuf = &(*stack->rxbuf)[idxf];
|
||||
/* put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idxf] - ETH_HEADERSIZE);
|
||||
/* mark as received */
|
||||
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
|
||||
(*stack->rxsa)[idxf] = oshw_ntohs(ehp->sa1);
|
||||
break;
|
||||
} else {
|
||||
OSEE_PRINT("ecx_inframe(): WARNING: strange things happened\n");
|
||||
/* strange things happened */
|
||||
}
|
||||
} else {
|
||||
OSEE_PRINT("ecx_inframe(): WARNING it is NOT an EtherCAT frame!\n");
|
||||
}
|
||||
} else {
|
||||
// WARNING: no messages received.
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
ee_port_unlock();
|
||||
|
||||
}
|
||||
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
/** Blocking redundant receive frame function. If redundant mode is not active then
|
||||
* it skips the secondary stack and redundancy functions. In redundant mode it waits
|
||||
* for both (primary and secondary) frames to come in. The result goes in an decision
|
||||
* tree that decides, depending on the route of the packet and its possible missing arrival,
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] timer = absolute timeout time
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
wkc2 = 0;
|
||||
do {
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
wkc = ecx_inframe(port, idx, 0);
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE) {
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE) {
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
/* primary socket got secondary frame and secondary socket got primary frame */
|
||||
/* normal situation in redundant mode */
|
||||
if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) ) {
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) ) {
|
||||
/* If both primary and secondary have partial connection retransmit the primary received
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) ) {
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port, idx, 1);
|
||||
do {
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
|
||||
if (wkc2 > EC_NOFRAME) {
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
*
|
||||
* The function calls ec_outframe_red() and ec_waitinframe_red().
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index of frame
|
||||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
||||
osal_timer_start (&timer1, timeout);
|
||||
do {
|
||||
/* tx frame on primary and if in redundant mode a dummy on secondary */
|
||||
ecx_outframe_red(port, idx);
|
||||
if (timeout < EC_TIMEOUTRET) {
|
||||
osal_timer_start (&timer2, timeout);
|
||||
} else {
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly
|
||||
from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
||||
#ifdef EC_VER1
|
||||
int ec_setupnic(const char *ifname, int secondary)
|
||||
{
|
||||
return ecx_setupnic(&ecx_port, ifname, secondary);
|
||||
}
|
||||
|
||||
int ec_closenic(void)
|
||||
{
|
||||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
#endif
|
|
@ -0,0 +1,122 @@
|
|||
/*
|
||||
* 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 nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
#define _nicdrvh_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
typedef struct
|
||||
{
|
||||
/** socket connection used */
|
||||
int *sock;
|
||||
/** tx buffer */
|
||||
ec_bufT (*txbuf)[EC_MAXBUF];
|
||||
/** tx buffer lengths */
|
||||
int (*txbuflength)[EC_MAXBUF];
|
||||
/** temporary receive buffer */
|
||||
ec_bufT *tempbuf;
|
||||
/** rx buffers */
|
||||
ec_bufT (*rxbuf)[EC_MAXBUF];
|
||||
/** rx buffer status fields */
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
|
||||
/** pointer structure to buffers for redundant port */
|
||||
typedef struct
|
||||
{
|
||||
ec_stackT stack;
|
||||
int sockhandle;
|
||||
/** rx buffers */
|
||||
ec_bufT rxbuf[EC_MAXBUF];
|
||||
/** rx buffer status */
|
||||
int rxbufstat[EC_MAXBUF];
|
||||
/** rx MAC source address */
|
||||
int rxsa[EC_MAXBUF];
|
||||
/** temporary rx buffer */
|
||||
ec_bufT tempinbuf;
|
||||
} ecx_redportt;
|
||||
|
||||
/** pointer structure to buffers, vars and mutexes for port instantiation */
|
||||
typedef struct
|
||||
{
|
||||
ec_stackT stack;
|
||||
int sockhandle;
|
||||
/** rx buffers */
|
||||
ec_bufT rxbuf[EC_MAXBUF];
|
||||
/** rx buffer status */
|
||||
int rxbufstat[EC_MAXBUF];
|
||||
/** rx MAC source address */
|
||||
int rxsa[EC_MAXBUF];
|
||||
/** temporary rx buffer */
|
||||
ec_bufT tempinbuf;
|
||||
/** temporary rx buffer status */
|
||||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
|
||||
/** Device id in the device pool */
|
||||
int dev_id;
|
||||
|
||||
// TODO: add mutex support
|
||||
} ecx_portt;
|
||||
|
||||
extern const uint16 priMAC[3];
|
||||
extern const uint16 secMAC[3];
|
||||
|
||||
#ifdef EC_VER1
|
||||
extern ecx_portt ecx_port;
|
||||
extern ecx_redportt ecx_redport;
|
||||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
int ec_inframe(uint8 idx, int stacknumber);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,79 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include "oshw.h"
|
||||
#include "intel_i210.h"
|
||||
#include "ethercat.h"
|
||||
|
||||
#if !defined(__gnu_linux__)
|
||||
#include <machine/endian.h>
|
||||
#else
|
||||
#include <endian.h>
|
||||
#define __htons(x) htobe16(x)
|
||||
#define __ntohs(x) be16toh(x)
|
||||
#endif
|
||||
|
||||
ec_adaptert adapters [DEVS_MAX_NB];
|
||||
|
||||
/**
|
||||
* Host to Network byte order (i.e. to big endian).
|
||||
*
|
||||
* Note that Ethercat uses little endian byte order, except for the Ethernet
|
||||
* header which is big endian as usual.
|
||||
*/
|
||||
inline uint16 oshw_htons(uint16 host)
|
||||
{
|
||||
// __htons() is provided by the bare-metal x86 compiler
|
||||
return __htons(host);
|
||||
}
|
||||
|
||||
/**
|
||||
* Network (i.e. big endian) to Host byte order.
|
||||
*
|
||||
* Note that Ethercat uses little endian byte order, except for the Ethernet
|
||||
* header which is big endian as usual.
|
||||
*/
|
||||
inline uint16 oshw_ntohs(uint16 network)
|
||||
{
|
||||
// __ntohs() is provided by the bare-metal x86 compiler
|
||||
return __ntohs(network);
|
||||
}
|
||||
|
||||
/** Create list over available network adapters.
|
||||
* @return First element in linked list of adapters
|
||||
*/
|
||||
ec_adaptert* oshw_find_adapters(void)
|
||||
{
|
||||
ec_adaptert *ret = NULL;
|
||||
if (eth_discover_devices() >= 0) {
|
||||
for (int i = 0;; ++i) {
|
||||
struct eth_device *dev = eth_get_device(i);
|
||||
if (dev == NULL) {
|
||||
adapters[i-1].next = NULL;
|
||||
break;
|
||||
}
|
||||
strncpy(adapters[i].name, dev->name, MAX_DEVICE_NAME);
|
||||
adapters[i].next = &adapters[i+1];
|
||||
}
|
||||
ret = &(adapters[0]);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/** Free memory allocated memory used by adapter collection.
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
void oshw_free_adapters(ec_adaptert *adapter)
|
||||
{
|
||||
}
|
||||
|
||||
extern int ec_slavecount;
|
||||
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* 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 ethercatbase.c
|
||||
*/
|
||||
|
||||
#ifndef _oshw_
|
||||
#define _oshw_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include "ethercattype.h"
|
||||
#include "nicdrv.h"
|
||||
#include "ethercatmain.h"
|
||||
|
||||
uint16 oshw_htons(uint16 hostshort);
|
||||
uint16 oshw_ntohs(uint16 networkshort);
|
||||
ec_adaptert* oshw_find_adapters(void);
|
||||
void oshw_free_adapters(ec_adaptert * adapter);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -8,10 +8,10 @@
|
|||
* EtherCAT RAW socket driver.
|
||||
*
|
||||
* Low level interface functions to send and receive EtherCAT packets.
|
||||
* EtherCAT has the property that packets are only send by the master,
|
||||
* and the send packets always return in the receive buffer.
|
||||
* EtherCAT has the property that packets are only sent by the master,
|
||||
* and the sent packets always return in the receive buffer.
|
||||
* There can be multiple packets "on the wire" before they return.
|
||||
* To combine the received packets with the original send packets a buffer
|
||||
* To combine the received packets with the original sent packets a buffer
|
||||
* system is installed. The identifier is put in the index item of the
|
||||
* EtherCAT header. The index is stored and compared when a frame is received.
|
||||
* If there is a match the packet can be combined with the transmit packet
|
||||
|
@ -46,7 +46,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -246,7 +246,7 @@ int ecx_closenic(ecx_portt *port)
|
|||
return 0;
|
||||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
/** Fill buffer with Ethernet header structure.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
|
@ -267,10 +267,10 @@ void ec_setupheader(void *p)
|
|||
/** Get new frame identifier index and allocate corresponding rx buffer.
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
uint8 idx;
|
||||
int cnt;
|
||||
uint8 cnt;
|
||||
|
||||
WaitForRtControl(port->getindex_region);
|
||||
|
||||
|
@ -307,7 +307,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -321,7 +321,7 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
HPESTATUS status;
|
||||
DWORD txstate;
|
||||
|
@ -363,15 +363,16 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
log_RT_event('S',(WORD)3);
|
||||
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
status = hpeStartTransmitter(port->handle);
|
||||
if (status != E_OK)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
result = -3;
|
||||
goto end;
|
||||
}
|
||||
|
||||
log_RT_event('S',(WORD)4);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
result = lp;
|
||||
|
||||
end:
|
||||
|
@ -383,7 +384,7 @@ end:
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
HPESTATUS status;
|
||||
ec_comt *datagramP;
|
||||
|
@ -408,9 +409,13 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
//send(sockhandle2, &ec_txbuf2, ec_txbuflength2 , 0);
|
||||
// OBS! redundant not ACTIVE for BFIN, just added to compile
|
||||
//ASSERT (0);
|
||||
hpeAttachTransmitBufferSet(port->redport->handle, port->tx_buffers[idx]);
|
||||
status = hpeStartTransmitter(port->redport->handle);
|
||||
hpeAttachTransmitBufferSet(port->redport->handle, port->tx_buffers[idx]);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
status = hpeStartTransmitter(port->redport->handle);
|
||||
if (status != E_OK)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
}
|
||||
|
||||
return rval;
|
||||
|
@ -454,7 +459,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retreives it
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
|
@ -466,7 +471,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
|
@ -510,7 +515,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
|
@ -540,7 +545,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ReleaseRtControl();
|
||||
}
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
|
@ -555,7 +560,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
|
@ -586,10 +591,10 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
@ -641,7 +646,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
@ -665,7 +670,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -676,7 +681,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1;
|
||||
|
@ -701,37 +706,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -67,14 +67,14 @@ typedef struct
|
|||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -97,20 +97,20 @@ extern const uint16 secMAC[3];
|
|||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setupheader(void *p);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int sock);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -52,7 +52,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -95,6 +95,7 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
struct ifreq ifr;
|
||||
struct sockaddr_ll sll;
|
||||
int *psock;
|
||||
pthread_mutexattr_t mutexattr;
|
||||
|
||||
rval = 0;
|
||||
if (secondary)
|
||||
|
@ -123,9 +124,11 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
}
|
||||
else
|
||||
{
|
||||
pthread_mutex_init(&(port->getindex_mutex), NULL);
|
||||
pthread_mutex_init(&(port->tx_mutex) , NULL);
|
||||
pthread_mutex_init(&(port->rx_mutex) , NULL);
|
||||
pthread_mutexattr_init(&mutexattr);
|
||||
pthread_mutexattr_setprotocol(&mutexattr , PTHREAD_PRIO_INHERIT);
|
||||
pthread_mutex_init(&(port->getindex_mutex), &mutexattr);
|
||||
pthread_mutex_init(&(port->tx_mutex) , &mutexattr);
|
||||
pthread_mutex_init(&(port->rx_mutex) , &mutexattr);
|
||||
port->sockhandle = -1;
|
||||
port->lastidx = 0;
|
||||
port->redstate = ECT_RED_NONE;
|
||||
|
@ -212,10 +215,10 @@ void ec_setupheader(void *p)
|
|||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
int idx;
|
||||
int cnt;
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
pthread_mutex_lock( &(port->getindex_mutex) );
|
||||
|
||||
|
@ -251,7 +254,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -264,7 +267,7 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp, rval;
|
||||
ec_stackT *stack;
|
||||
|
@ -278,8 +281,12 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
stack = &(port->redport->stack);
|
||||
}
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
rval = send(*stack->sock, (*stack->txbuf)[idx], lp, 0);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = send(*stack->sock, (*stack->txbuf)[idx], lp, 0);
|
||||
if (rval == -1)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -289,7 +296,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
|
@ -311,9 +318,12 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
/* rewrite MAC source address 1 to secondary */
|
||||
ehp->sa1 = htons(secMAC[1]);
|
||||
/* transmit over secondary socket */
|
||||
send(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2 , 0);
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
if (send(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2 , 0) == -1)
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
}
|
||||
|
||||
return rval;
|
||||
|
@ -347,7 +357,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retreives it
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
|
@ -360,11 +370,11 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
int idxf;
|
||||
uint8 idxf;
|
||||
ec_etherheadert *ehp;
|
||||
ec_comt *ecp;
|
||||
ec_stackT *stack;
|
||||
|
@ -403,7 +413,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
|
@ -429,7 +439,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
/* strange things happened */
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -438,7 +448,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
|
||||
}
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
|
@ -454,7 +464,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
|
@ -481,10 +491,10 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
@ -537,23 +547,18 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -565,7 +570,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
@ -581,18 +586,13 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
@ -608,37 +608,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -69,14 +69,14 @@ typedef struct
|
|||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -95,23 +95,23 @@ extern ecx_redportt ecx_redport;
|
|||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int sock);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -42,7 +42,6 @@ uint16 oshw_ntohs(uint16 network)
|
|||
ec_adaptert * oshw_find_adapters(void)
|
||||
{
|
||||
int i;
|
||||
int string_len;
|
||||
struct if_nameindex *ids;
|
||||
ec_adaptert * adapter;
|
||||
ec_adaptert * prev_adapter;
|
||||
|
@ -50,7 +49,7 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
|
||||
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
* decsription.
|
||||
* description.
|
||||
*/
|
||||
|
||||
ids = if_nameindex ();
|
||||
|
@ -70,20 +69,15 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
ret_adapter = adapter;
|
||||
}
|
||||
|
||||
/* fetch description and name, in linux we use the same on both */
|
||||
/* fetch description and name, in Linux we use the same on both */
|
||||
adapter->next = NULL;
|
||||
|
||||
if (ids[i].if_name)
|
||||
{
|
||||
string_len = strlen(ids[i].if_name);
|
||||
if (string_len > (EC_MAXLEN_ADAPTERNAME - 1))
|
||||
{
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->name, ids[i].if_name,string_len);
|
||||
adapter->name[string_len] = '\0';
|
||||
strncpy(adapter->desc, ids[i].if_name,string_len);
|
||||
adapter->desc[string_len] = '\0';
|
||||
strncpy(adapter->name, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->name[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
strncpy(adapter->desc, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->desc[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -106,7 +100,7 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
void oshw_free_adapters(ec_adaptert * adapter)
|
||||
{
|
||||
ec_adaptert * next_adapter;
|
||||
/* Iterate the linked list and free all elemnts holding
|
||||
/* Iterate the linked list and free all elements holding
|
||||
* adapter information
|
||||
*/
|
||||
if(adapter)
|
||||
|
|
|
@ -0,0 +1,649 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* EtherCAT RAW socket driver.
|
||||
*
|
||||
* Low level interface functions to send and receive EtherCAT packets.
|
||||
* EtherCAT has the property that packets are only send by the master,
|
||||
* and the send packets always return in the receive buffer.
|
||||
* There can be multiple packets "on the wire" before they return.
|
||||
* To combine the received packets with the original send packets a buffer
|
||||
* system is installed. The identifier is put in the index item of the
|
||||
* EtherCAT header. The index is stored and compared when a frame is received.
|
||||
* If there is a match the packet can be combined with the transmit packet
|
||||
* and returned to the higher level function.
|
||||
*
|
||||
* The socket layer can exhibit a reversal in the packet order (rare).
|
||||
* If the Tx order is A-B-C the return order could be A-C-B. The indexed buffer
|
||||
* will reorder the packets automatically.
|
||||
*
|
||||
* The "redundant" option will configure two sockets and two NIC interfaces.
|
||||
* Slaves are connected to both interfaces, one on the IN port and one on the
|
||||
* OUT port. Packets are send via both interfaces. Any one of the connections
|
||||
* (also an interconnect) can be removed and the slaves are still serviced with
|
||||
* packets. The software layer will detect the possible failure modes and
|
||||
* compensate. If needed the packets from interface A are resent through interface B.
|
||||
* This layer is fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
|
||||
#include <assert.h>
|
||||
#include <sys/types.h>
|
||||
#include <stdio.h>
|
||||
#include <fcntl.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "ethercattype.h"
|
||||
#include "nicdrv.h"
|
||||
#include "osal.h"
|
||||
|
||||
/** Redundancy modes */
|
||||
enum
|
||||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
/** Primary source MAC address used for EtherCAT.
|
||||
* This address is not the MAC address used from the NIC.
|
||||
* EtherCAT does not care about MAC addressing, but it is used here to
|
||||
* differentiate the route the packet traverses through the EtherCAT
|
||||
* segment. This is needed to fund out the packet flow in redundant
|
||||
* configurations. */
|
||||
const uint16 priMAC[3] = { 0x0101, 0x0101, 0x0101 };
|
||||
/** Secondary source MAC address used for EtherCAT. */
|
||||
const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
|
||||
|
||||
/** second MAC word is used for identification */
|
||||
#define RX_PRIM priMAC[1]
|
||||
/** second MAC word is used for identification */
|
||||
#define RX_SEC secMAC[1]
|
||||
|
||||
static char errbuf[PCAP_ERRBUF_SIZE];
|
||||
|
||||
static void ecx_clear_rxbufstat(int *rxbufstat)
|
||||
{
|
||||
int i;
|
||||
for(i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
}
|
||||
|
||||
/** Basic setup to connect NIC to socket.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] ifname = Name of NIC device, f.e. "eth0"
|
||||
* @param[in] secondary = if >0 then use secondary stack instead of primary
|
||||
* @return >0 if succeeded
|
||||
*/
|
||||
int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
||||
{
|
||||
int i, rval;
|
||||
pcap_t **psock;
|
||||
|
||||
rval = 0;
|
||||
if (secondary)
|
||||
{
|
||||
/* secondary port struct available? */
|
||||
if (port->redport)
|
||||
{
|
||||
/* when using secondary socket it is automatically a redundant setup */
|
||||
psock = &(port->redport->sockhandle);
|
||||
*psock = NULL;
|
||||
port->redstate = ECT_RED_DOUBLE;
|
||||
port->redport->stack.sock = &(port->redport->sockhandle);
|
||||
port->redport->stack.txbuf = &(port->txbuf);
|
||||
port->redport->stack.txbuflength = &(port->txbuflength);
|
||||
port->redport->stack.tempbuf = &(port->redport->tempinbuf);
|
||||
port->redport->stack.rxbuf = &(port->redport->rxbuf);
|
||||
port->redport->stack.rxbufstat = &(port->redport->rxbufstat);
|
||||
port->redport->stack.rxsa = &(port->redport->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->redport->rxbufstat[0]));
|
||||
}
|
||||
else
|
||||
{
|
||||
/* fail */
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
pthread_mutex_init(&(port->getindex_mutex), NULL);
|
||||
pthread_mutex_init(&(port->tx_mutex), NULL);
|
||||
pthread_mutex_init(&(port->rx_mutex), NULL);
|
||||
port->sockhandle = NULL;
|
||||
port->lastidx = 0;
|
||||
port->redstate = ECT_RED_NONE;
|
||||
port->stack.sock = &(port->sockhandle);
|
||||
port->stack.txbuf = &(port->txbuf);
|
||||
port->stack.txbuflength = &(port->txbuflength);
|
||||
port->stack.tempbuf = &(port->tempinbuf);
|
||||
port->stack.rxbuf = &(port->rxbuf);
|
||||
port->stack.rxbufstat = &(port->rxbufstat);
|
||||
port->stack.rxsa = &(port->rxsa);
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
psock = &(port->sockhandle);
|
||||
}
|
||||
*psock = pcap_open_live(ifname, 65536, 1, 0, errbuf);
|
||||
if (NULL == *psock)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
rval = pcap_setdirection(*psock, PCAP_D_IN);
|
||||
if (rval != 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
rval = pcap_setnonblock(*psock, 1, errbuf);
|
||||
if (rval != 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
ec_setupheader(&(port->txbuf[i]));
|
||||
port->rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
ec_setupheader(&(port->txbuf2));
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
/** Close sockets used
|
||||
* @param[in] port = port context struct
|
||||
* @return 0
|
||||
*/
|
||||
int ecx_closenic(ecx_portt *port)
|
||||
{
|
||||
if (port->sockhandle != NULL)
|
||||
{
|
||||
pthread_mutex_destroy(&(port->getindex_mutex));
|
||||
pthread_mutex_destroy(&(port->tx_mutex));
|
||||
pthread_mutex_destroy(&(port->rx_mutex));
|
||||
pcap_close(port->sockhandle);
|
||||
port->sockhandle = NULL;
|
||||
}
|
||||
if ((port->redport) && (port->redport->sockhandle != NULL))
|
||||
{
|
||||
pcap_close(port->redport->sockhandle);
|
||||
port->redport->sockhandle = NULL;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
{
|
||||
ec_etherheadert *bp;
|
||||
bp = p;
|
||||
bp->da0 = htons(0xffff);
|
||||
bp->da1 = htons(0xffff);
|
||||
bp->da2 = htons(0xffff);
|
||||
bp->sa0 = htons(priMAC[0]);
|
||||
bp->sa1 = htons(priMAC[1]);
|
||||
bp->sa2 = htons(priMAC[2]);
|
||||
bp->etype = htons(ETH_P_ECAT);
|
||||
}
|
||||
|
||||
/** Get new frame identifier index and allocate corresponding rx buffer.
|
||||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
pthread_mutex_lock(&(port->getindex_mutex));
|
||||
|
||||
idx = port->lastidx + 1;
|
||||
/* index can't be larger than buffer array */
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
cnt = 0;
|
||||
/* try to find unused index */
|
||||
while ((port->rxbufstat[idx] != EC_BUF_EMPTY) && (cnt < EC_MAXBUF))
|
||||
{
|
||||
idx++;
|
||||
cnt++;
|
||||
if (idx >= EC_MAXBUF)
|
||||
{
|
||||
idx = 0;
|
||||
}
|
||||
}
|
||||
port->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
port->lastidx = idx;
|
||||
|
||||
pthread_mutex_unlock(&(port->getindex_mutex));
|
||||
|
||||
return idx;
|
||||
}
|
||||
|
||||
/** Set rx buffer status.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
port->redport->rxbufstat[idx] = bufstat;
|
||||
}
|
||||
|
||||
/** Transmit buffer over socket (non blocking).
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in tx buffer array
|
||||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp, rval;
|
||||
ec_stackT *stack;
|
||||
|
||||
if (!stacknumber)
|
||||
{
|
||||
stack = &(port->stack);
|
||||
}
|
||||
else
|
||||
{
|
||||
stack = &(port->redport->stack);
|
||||
}
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = pcap_sendpacket(*stack->sock, (*stack->txbuf)[idx], lp);
|
||||
if (rval == PCAP_ERROR)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
/** Transmit buffer over socket (non blocking).
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
int rval;
|
||||
|
||||
ehp = (ec_etherheadert *)&(port->txbuf[idx]);
|
||||
/* rewrite MAC source address 1 to primary */
|
||||
ehp->sa1 = htons(priMAC[1]);
|
||||
/* transmit over primary socket*/
|
||||
rval = ecx_outframe(port, idx, 0);
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
pthread_mutex_lock( &(port->tx_mutex) );
|
||||
ehp = (ec_etherheadert *)&(port->txbuf2);
|
||||
/* use dummy frame for secondary socket transmit (BRD) */
|
||||
datagramP = (ec_comt*)&(port->txbuf2[ETH_HEADERSIZE]);
|
||||
/* write index to frame */
|
||||
datagramP->index = idx;
|
||||
/* rewrite MAC source address 1 to secondary */
|
||||
ehp->sa1 = htons(secMAC[1]);
|
||||
/* transmit over secondary socket */
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
if (pcap_sendpacket(port->redport->sockhandle, (u_char const *)&(port->txbuf2), port->txbuflength2) == PCAP_ERROR)
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
||||
/** Non blocking read of socket. Put frame in temporary buffer.
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
* @return >0 if frame is available and read
|
||||
*/
|
||||
static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
||||
{
|
||||
int lp, bytesrx;
|
||||
ec_stackT *stack;
|
||||
struct pcap_pkthdr * header;
|
||||
unsigned char const * pkt_data;
|
||||
int res;
|
||||
|
||||
if (!stacknumber)
|
||||
{
|
||||
stack = &(port->stack);
|
||||
}
|
||||
else
|
||||
{
|
||||
stack = &(port->redport->stack);
|
||||
}
|
||||
lp = sizeof(port->tempinbuf);
|
||||
|
||||
res = pcap_next_ex(*stack->sock, &header, &pkt_data);
|
||||
if (res <=0 )
|
||||
{
|
||||
port->tempinbufs = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
bytesrx = header->len;
|
||||
if (bytesrx > lp)
|
||||
{
|
||||
bytesrx = lp;
|
||||
}
|
||||
memcpy(*stack->tempbuf, pkt_data, bytesrx);
|
||||
port->tempinbufs = bytesrx;
|
||||
return (bytesrx > 0);
|
||||
}
|
||||
|
||||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
* than requested index, store in buffer and exit. 3 frame read with matching
|
||||
* index, store in buffer, set completed flag in buffer status and exit.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] stacknumber = 0=primary 1=secondary stack
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
uint8 idxf;
|
||||
ec_etherheadert *ehp;
|
||||
ec_comt *ecp;
|
||||
ec_stackT *stack;
|
||||
ec_bufT *rxbuf;
|
||||
|
||||
if (!stacknumber)
|
||||
{
|
||||
stack = &(port->stack);
|
||||
}
|
||||
else
|
||||
{
|
||||
stack = &(port->redport->stack);
|
||||
}
|
||||
rval = EC_NOFRAME;
|
||||
rxbuf = &(*stack->rxbuf)[idx];
|
||||
/* check if requested index is already in buffer ? */
|
||||
if ((idx < EC_MAXBUF) && ((*stack->rxbufstat)[idx] == EC_BUF_RCVD))
|
||||
{
|
||||
l = (*rxbuf)[0] + ((uint16)((*rxbuf)[1] & 0x0f) << 8);
|
||||
/* return WKC */
|
||||
rval = ((*rxbuf)[l] + ((uint16)(*rxbuf)[l + 1] << 8));
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
}
|
||||
else
|
||||
{
|
||||
pthread_mutex_lock(&(port->rx_mutex));
|
||||
/* non blocking call to retrieve frame from socket */
|
||||
if (ecx_recvpkt(port, stacknumber))
|
||||
{
|
||||
rval = EC_OTHERFRAME;
|
||||
ehp =(ec_etherheadert*)(stack->tempbuf);
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (ehp->etype == htons(ETH_P_ECAT))
|
||||
{
|
||||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idx] - ETH_HEADERSIZE);
|
||||
/* return WKC */
|
||||
rval = ((*rxbuf)[l] + ((uint16)((*rxbuf)[l + 1]) << 8));
|
||||
/* mark as completed */
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_COMPLETE;
|
||||
/* store MAC source word 1 for redundant routing info */
|
||||
(*stack->rxsa)[idx] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* check if index exist and someone is waiting for it */
|
||||
if (idxf < EC_MAXBUF && (*stack->rxbufstat)[idxf] == EC_BUF_TX)
|
||||
{
|
||||
rxbuf = &(*stack->rxbuf)[idxf];
|
||||
/* put it in the buffer array (strip ethernet header) */
|
||||
memcpy(rxbuf, &(*stack->tempbuf)[ETH_HEADERSIZE], (*stack->txbuflength)[idxf] - ETH_HEADERSIZE);
|
||||
/* mark as received */
|
||||
(*stack->rxbufstat)[idxf] = EC_BUF_RCVD;
|
||||
(*stack->rxsa)[idxf] = ntohs(ehp->sa1);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* strange things happened */
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
pthread_mutex_unlock( &(port->rx_mutex) );
|
||||
|
||||
}
|
||||
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
/** Blocking redundant receive frame function. If redundant mode is not active then
|
||||
* it skips the secondary stack and redundancy functions. In redundant mode it waits
|
||||
* for both (primary and secondary) frames to come in. The result goes in an decision
|
||||
* tree that decides, depending on the route of the packet and its possible missing arrival,
|
||||
* how to reroute the original packet to get the data in an other try.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] tvs = timeout
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
int primrx, secrx;
|
||||
|
||||
/* if not in redundant mode then always assume secondary is OK */
|
||||
if (port->redstate == ECT_RED_NONE)
|
||||
wkc2 = 0;
|
||||
do
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
wkc = ecx_inframe(port, idx, 0);
|
||||
/* only try secondary if in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* only read frame if not already in */
|
||||
if (wkc2 <= EC_NOFRAME)
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
}
|
||||
/* wait for both frames to arrive or timeout */
|
||||
} while (((wkc <= EC_NOFRAME) || (wkc2 <= EC_NOFRAME)) && !osal_timer_is_expired(timer));
|
||||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
/* primary socket got secondary frame and secondary socket got primary frame */
|
||||
/* normal situation in redundant mode */
|
||||
if ( ((primrx == RX_SEC) && (secrx == RX_PRIM)) )
|
||||
{
|
||||
/* copy secondary buffer to primary */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
/* primary socket got nothing or primary frame, and secondary socket got secondary frame */
|
||||
/* we need to resend TX packet */
|
||||
if ( ((primrx == 0) && (secrx == RX_SEC)) ||
|
||||
((primrx == RX_PRIM) && (secrx == RX_SEC)) )
|
||||
{
|
||||
/* If both primary and secondary have partial connection retransmit the primary received
|
||||
* frame over the secondary socket. The result from the secondary received frame is a combined
|
||||
* frame that traversed all slaves in standard order. */
|
||||
if ( (primrx == RX_PRIM) && (secrx == RX_SEC) )
|
||||
{
|
||||
/* copy primary rx to tx buffer */
|
||||
memcpy(&(port->txbuf[idx][ETH_HEADERSIZE]), &(port->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
}
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
/* resend secondary tx */
|
||||
ecx_outframe(port, idx, 1);
|
||||
do
|
||||
{
|
||||
/* retrieve frame */
|
||||
wkc2 = ecx_inframe(port, idx, 1);
|
||||
} while ((wkc2 <= EC_NOFRAME) && !osal_timer_is_expired(&timer2));
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
/* copy secondary result to primary rx buffer */
|
||||
memcpy(&(port->rxbuf[idx]), &(port->redport->rxbuf[idx]), port->txbuflength[idx] - ETH_HEADERSIZE);
|
||||
wkc = wkc2;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* return WKC or EC_NOFRAME */
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking receive frame function. Calls ec_waitinframe_red().
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
*
|
||||
* The function calls ec_outframe_red() and ec_waitinframe_red().
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = index of frame
|
||||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
||||
osal_timer_start (&timer1, timeout);
|
||||
do
|
||||
{
|
||||
/* tx frame on primary and if in redundant mode a dummy on secondary */
|
||||
ecx_outframe_red(port, idx);
|
||||
if (timeout < EC_TIMEOUTRET)
|
||||
{
|
||||
osal_timer_start (&timer2, timeout);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
||||
#ifdef EC_VER1
|
||||
|
||||
int ec_setupnic(const char *ifname, int secondary)
|
||||
{
|
||||
return ecx_setupnic(&ecx_port, ifname, secondary);
|
||||
}
|
||||
|
||||
int ec_closenic(void)
|
||||
{
|
||||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,120 @@
|
|||
/*
|
||||
* 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 nicdrv.c
|
||||
*/
|
||||
|
||||
#ifndef _nicdrvh_
|
||||
#define _nicdrvh_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <pcap/pcap.h>
|
||||
|
||||
/** pointer structure to Tx and Rx stacks */
|
||||
typedef struct
|
||||
{
|
||||
/** socket connection used */
|
||||
pcap_t **sock;
|
||||
/** tx buffer */
|
||||
ec_bufT (*txbuf)[EC_MAXBUF];
|
||||
/** tx buffer lengths */
|
||||
int (*txbuflength)[EC_MAXBUF];
|
||||
/** temporary receive buffer */
|
||||
ec_bufT *tempbuf;
|
||||
/** rx buffers */
|
||||
ec_bufT (*rxbuf)[EC_MAXBUF];
|
||||
/** rx buffer status fields */
|
||||
int (*rxbufstat)[EC_MAXBUF];
|
||||
/** received MAC source address (middle word) */
|
||||
int (*rxsa)[EC_MAXBUF];
|
||||
} ec_stackT;
|
||||
|
||||
/** pointer structure to buffers for redundant port */
|
||||
typedef struct
|
||||
{
|
||||
ec_stackT stack;
|
||||
pcap_t *sockhandle;
|
||||
/** rx buffers */
|
||||
ec_bufT rxbuf[EC_MAXBUF];
|
||||
/** rx buffer status */
|
||||
int rxbufstat[EC_MAXBUF];
|
||||
/** rx MAC source address */
|
||||
int rxsa[EC_MAXBUF];
|
||||
/** temporary rx buffer */
|
||||
ec_bufT tempinbuf;
|
||||
} ecx_redportt;
|
||||
|
||||
/** pointer structure to buffers, vars and mutexes for port instantiation */
|
||||
typedef struct
|
||||
{
|
||||
ec_stackT stack;
|
||||
pcap_t *sockhandle;
|
||||
/** rx buffers */
|
||||
ec_bufT rxbuf[EC_MAXBUF];
|
||||
/** rx buffer status */
|
||||
int rxbufstat[EC_MAXBUF];
|
||||
/** rx MAC source address */
|
||||
int rxsa[EC_MAXBUF];
|
||||
/** temporary rx buffer */
|
||||
ec_bufT tempinbuf;
|
||||
/** temporary rx buffer status */
|
||||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
ecx_redportt *redport;
|
||||
pthread_mutex_t getindex_mutex;
|
||||
pthread_mutex_t tx_mutex;
|
||||
pthread_mutex_t rx_mutex;
|
||||
} ecx_portt;
|
||||
|
||||
extern const uint16 priMAC[3];
|
||||
extern const uint16 secMAC[3];
|
||||
|
||||
#ifdef EC_VER1
|
||||
extern ecx_portt ecx_port;
|
||||
extern ecx_redportt ecx_redport;
|
||||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,117 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
#include <sys/ioctl.h>
|
||||
#include <net/if.h>
|
||||
#include <sys/socket.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "oshw.h"
|
||||
|
||||
/**
|
||||
* Host to Network byte order (i.e. to big endian).
|
||||
*
|
||||
* Note that Ethercat uses little endian byte order, except for the Ethernet
|
||||
* header which is big endian as usual.
|
||||
*/
|
||||
uint16 oshw_htons(uint16 host)
|
||||
{
|
||||
uint16 network = htons (host);
|
||||
return network;
|
||||
}
|
||||
|
||||
/**
|
||||
* Network (i.e. big endian) to Host byte order.
|
||||
*
|
||||
* Note that Ethercat uses little endian byte order, except for the Ethernet
|
||||
* header which is big endian as usual.
|
||||
*/
|
||||
uint16 oshw_ntohs(uint16 network)
|
||||
{
|
||||
uint16 host = ntohs (network);
|
||||
return host;
|
||||
}
|
||||
|
||||
/** Create list over available network adapters.
|
||||
* @return First element in linked list of adapters
|
||||
*/
|
||||
ec_adaptert * oshw_find_adapters(void)
|
||||
{
|
||||
int i;
|
||||
struct if_nameindex *ids;
|
||||
ec_adaptert * adapter;
|
||||
ec_adaptert * prev_adapter;
|
||||
ec_adaptert * ret_adapter = NULL;
|
||||
|
||||
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
* description.
|
||||
*/
|
||||
|
||||
ids = if_nameindex ();
|
||||
for(i = 0; ids[i].if_index != 0; i++)
|
||||
{
|
||||
adapter = (ec_adaptert *)malloc(sizeof(ec_adaptert));
|
||||
/* If we got more than one adapter save link list pointer to previous
|
||||
* adapter.
|
||||
* Else save as pointer to return.
|
||||
*/
|
||||
if (i)
|
||||
{
|
||||
prev_adapter->next = adapter;
|
||||
}
|
||||
else
|
||||
{
|
||||
ret_adapter = adapter;
|
||||
}
|
||||
|
||||
/* fetch description and name, in macosx we use the same on both */
|
||||
adapter->next = NULL;
|
||||
|
||||
if (ids[i].if_name)
|
||||
{
|
||||
strncpy(adapter->name, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->name[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
strncpy(adapter->desc, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->desc[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
adapter->name[0] = '\0';
|
||||
adapter->desc[0] = '\0';
|
||||
}
|
||||
|
||||
prev_adapter = adapter;
|
||||
}
|
||||
|
||||
if_freenameindex (ids);
|
||||
|
||||
return ret_adapter;
|
||||
}
|
||||
|
||||
/** Free memory allocated memory used by adapter collection.
|
||||
* @param[in] adapter = First element in linked list of adapters
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
void oshw_free_adapters(ec_adaptert * adapter)
|
||||
{
|
||||
ec_adaptert * next_adapter;
|
||||
/* Iterate the linked list and free all elements holding
|
||||
* adapter information
|
||||
*/
|
||||
if(adapter)
|
||||
{
|
||||
next_adapter = adapter->next;
|
||||
free (adapter);
|
||||
while (next_adapter)
|
||||
{
|
||||
adapter = next_adapter;
|
||||
next_adapter = adapter->next;
|
||||
free (adapter);
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* 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 ethercatbase.c
|
||||
*/
|
||||
|
||||
#ifndef _oshw_
|
||||
#define _oshw_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
#include "ethercattype.h"
|
||||
#include "nicdrv.h"
|
||||
#include "ethercatmain.h"
|
||||
|
||||
uint16 oshw_htons(uint16 hostshort);
|
||||
uint16 oshw_ntohs(uint16 networkshort);
|
||||
ec_adaptert * oshw_find_adapters(void);
|
||||
void oshw_free_adapters(ec_adaptert * adapter);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -53,7 +53,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -151,10 +151,11 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
sprintf(fname, "/dev/bpf%i", i);
|
||||
*bpf = open(fname, O_RDWR);
|
||||
}
|
||||
|
||||
|
||||
if(*bpf == -1)
|
||||
{
|
||||
/* Failed to open bpf */
|
||||
perror("Could not open bpf\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -164,40 +165,52 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
if (ioctl(*bpf, BIOCSBLEN, &buffer_len) == -1) {
|
||||
perror("BIOCGBLEN");
|
||||
}
|
||||
assert(buffer_len >= 1518);
|
||||
|
||||
if (buffer_len < 1518) {
|
||||
printf("buffer_len %d < 1518\n", buffer_len);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* connect bpf to NIC by name */
|
||||
strcpy(ifr.ifr_name, ifname);
|
||||
assert(ioctl(*bpf, BIOCSETIF, &ifr) == 0);
|
||||
if(ioctl(*bpf, BIOCSETIF, &ifr) == -1) {
|
||||
perror("BIOCSETIF");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Set required bpf options */
|
||||
|
||||
/* Activate immediate mode */
|
||||
if (ioctl(*bpf, BIOCIMMEDIATE, &true_val) == -1) {
|
||||
perror("BIOCIMMEDIATE");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Set interface in promiscuous mode */
|
||||
if (ioctl(*bpf, BIOCPROMISC, &true_val) == -1) {
|
||||
perror("BIOCPROMISC");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Allow to have custom source address */
|
||||
if (ioctl(*bpf, BIOCSHDRCMPLT, &true_val) == -1) {
|
||||
perror("BIOCSHDRCMPLT");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Listen only to incomming messages */
|
||||
uint direction = BPF_D_IN;
|
||||
if (ioctl(*bpf, BIOCSDIRECTION, &direction) == -1) {
|
||||
perror("BIOCSDIRECTION");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Set read timeout */
|
||||
timeout.tv_sec = 0;
|
||||
timeout.tv_usec = 1;
|
||||
timeout.tv_usec = 11000;
|
||||
if (ioctl(*bpf, BIOCSRTIMEOUT, &timeout) == -1) {
|
||||
perror("BIOCSRTIMEOUT");
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
|
@ -207,9 +220,8 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
port->rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
ec_setupheader(&(port->txbuf2));
|
||||
if (r == 0) rval = 1;
|
||||
|
||||
return rval;
|
||||
return 1;
|
||||
}
|
||||
|
||||
/** Close sockets used
|
||||
|
@ -248,10 +260,10 @@ void ec_setupheader(void *p)
|
|||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
int idx;
|
||||
int cnt;
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
pthread_mutex_lock( &(port->getindex_mutex) );
|
||||
|
||||
|
@ -287,7 +299,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -300,7 +312,7 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp, rval;
|
||||
ec_stackT *stack;
|
||||
|
@ -315,8 +327,12 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
//rval = send(*stack->sock, (*stack->txbuf)[idx], lp, 0);
|
||||
rval = write (*stack->sock,(*stack->txbuf)[idx], lp);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = write (*stack->sock,(*stack->txbuf)[idx], lp);
|
||||
if (rval == -1)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -326,7 +342,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
|
@ -349,9 +365,12 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
ehp->sa1 = htons(secMAC[1]);
|
||||
/* transmit over secondary socket */
|
||||
//send(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2 , 0);
|
||||
write(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2);
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
if (write(port->redport->sockhandle, &(port->txbuf2), port->txbuflength2) == -1)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
pthread_mutex_unlock( &(port->tx_mutex) );
|
||||
}
|
||||
|
||||
return rval;
|
||||
|
@ -386,7 +405,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retreives it
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
|
@ -399,11 +418,11 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
int idxf;
|
||||
uint8 idxf;
|
||||
ec_etherheadert *ehp;
|
||||
ec_comt *ecp;
|
||||
ec_stackT *stack;
|
||||
|
@ -445,7 +464,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ecp =(ec_comt*)(&ehp[1]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip headers) */
|
||||
|
@ -471,7 +490,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
/* strange things happened */
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -480,7 +499,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
|
||||
}
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
|
@ -496,7 +515,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
|
@ -523,10 +542,10 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
@ -579,23 +598,18 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -607,7 +621,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
@ -623,18 +637,13 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
@ -650,37 +659,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -69,14 +69,14 @@ typedef struct
|
|||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -95,23 +95,23 @@ extern ecx_redportt ecx_redport;
|
|||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int sock);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -42,7 +42,6 @@ uint16 oshw_ntohs(uint16 network)
|
|||
ec_adaptert * oshw_find_adapters(void)
|
||||
{
|
||||
int i;
|
||||
int string_len;
|
||||
struct if_nameindex *ids;
|
||||
ec_adaptert * adapter;
|
||||
ec_adaptert * prev_adapter;
|
||||
|
@ -50,7 +49,7 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
|
||||
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
* decsription.
|
||||
* description.
|
||||
*/
|
||||
|
||||
ids = if_nameindex ();
|
||||
|
@ -70,20 +69,15 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
ret_adapter = adapter;
|
||||
}
|
||||
|
||||
/* fetch description and name, in linux we use the same on both */
|
||||
/* fetch description and name, in rtems we use the same on both */
|
||||
adapter->next = NULL;
|
||||
|
||||
if (ids[i].if_name)
|
||||
{
|
||||
string_len = strlen(ids[i].if_name);
|
||||
if (string_len > (EC_MAXLEN_ADAPTERNAME - 1))
|
||||
{
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->name, ids[i].if_name,string_len);
|
||||
adapter->name[string_len] = '\0';
|
||||
strncpy(adapter->desc, ids[i].if_name,string_len);
|
||||
adapter->desc[string_len] = '\0';
|
||||
strncpy(adapter->name, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->name[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
strncpy(adapter->desc, ids[i].if_name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->desc[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -106,7 +100,7 @@ ec_adaptert * oshw_find_adapters(void)
|
|||
void oshw_free_adapters(ec_adaptert * adapter)
|
||||
{
|
||||
ec_adaptert * next_adapter;
|
||||
/* Iterate the linked list and free all elemnts holding
|
||||
/* Iterate the linked list and free all elements holding
|
||||
* adapter information
|
||||
*/
|
||||
if(adapter)
|
||||
|
|
|
@ -51,7 +51,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -192,10 +192,10 @@ void ec_setupheader(void *p)
|
|||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
int idx;
|
||||
int cnt;
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
mtx_lock (port->getindex_mutex);
|
||||
|
||||
|
@ -233,7 +233,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -248,7 +248,7 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp, rval;
|
||||
ec_stackT *stack;
|
||||
|
@ -262,8 +262,8 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
stack = &(port->redport->stack);
|
||||
}
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
rval = bfin_EMAC_send((*stack->txbuf)[idx], lp);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = bfin_EMAC_send((*stack->txbuf)[idx], lp);
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -273,7 +273,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
|
@ -298,9 +298,9 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
//send(sockhandle2, &ec_txbuf2, ec_txbuflength2 , 0);
|
||||
// OBS! redundant not ACTIVE for BFIN, just added to compile
|
||||
ASSERT (0);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
bfin_EMAC_send(&(port->txbuf2), port->txbuflength2);
|
||||
mtx_unlock (port->tx_mutex);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
|
||||
return rval;
|
||||
|
@ -334,7 +334,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retreives it
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
|
@ -347,7 +347,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
|
@ -390,7 +390,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
|
@ -416,7 +416,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
/* strange things happened */
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -425,7 +425,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
|
||||
}
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
|
@ -441,7 +441,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert timer)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
int wkc2 = EC_NOFRAME;
|
||||
|
@ -471,13 +471,13 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME)
|
||||
{
|
||||
primrx = port->rxsa[idx];
|
||||
}
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
|
@ -534,23 +534,18 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert timer)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start (&timer, timeout);
|
||||
wkc = ecx_waitinframe_red(port, idx, timer);
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -562,7 +557,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer;
|
||||
|
@ -579,11 +574,6 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
|||
wkc = ecx_waitinframe_red(port, idx, read_timer);
|
||||
/* wait for answer with WKC>0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && (osal_timer_is_expired(&timer) == FALSE));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
@ -600,37 +590,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -62,14 +62,14 @@ typedef struct
|
|||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -88,22 +88,22 @@ extern ecx_redportt ecx_redport;
|
|||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int stacknumber);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int stacknumber);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -13,14 +13,14 @@
|
|||
* There can be multiple packets "on the wire" before they return.
|
||||
* To combine the received packets with the original send packets a buffer
|
||||
* system is installed. The identifier is put in the index item of the
|
||||
* EtherCAT header. The index is stored and compared when a frame is recieved.
|
||||
* EtherCAT header. The index is stored and compared when a frame is received.
|
||||
* If there is a match the packet can be combined with the transmit packet
|
||||
* and returned to the higher level function.
|
||||
*
|
||||
* If EtherCAT is run in parallel with normal IP traffic and EtherCAT have a
|
||||
* dedicated NIC, instatiate an extra tNetX task and redirect the NIC workQ
|
||||
* dedicated NIC, instantiate an extra tNetX task and redirect the NIC workQ
|
||||
* to be handle by the extra tNetX task, if needed raise the tNetX task prio.
|
||||
* This prevents from having tNet0 becoming a bootleneck.
|
||||
* This prevents from having tNet0 becoming a bottleneck.
|
||||
*
|
||||
* The "redundant" option will configure two Mux drivers and two NIC interfaces.
|
||||
* Slaves are connected to both interfaces, one on the IN port and one on the
|
||||
|
@ -31,11 +31,14 @@
|
|||
* This layer if fully transparent for the higher layers.
|
||||
*/
|
||||
|
||||
#include <vxWorks.h>
|
||||
#include <ctype.h>
|
||||
#include <string.h>
|
||||
#include <ipProto.h>
|
||||
#include <vxWorks.h>
|
||||
#include <wvLib.h>
|
||||
#include <stdio.h>
|
||||
#include <muxLib.h>
|
||||
#include <ipProto.h>
|
||||
#include <wvLib.h>
|
||||
#include <sysLib.h>
|
||||
|
||||
#include "oshw.h"
|
||||
#include "osal.h"
|
||||
|
@ -76,7 +79,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -96,6 +99,10 @@ const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
|
|||
/** second MAC word is used for identification */
|
||||
#define RX_SEC secMAC[1]
|
||||
|
||||
/* usec per tick for timeconversion, default to 1kHz */
|
||||
#define USECS_PER_SEC 1000000
|
||||
static unsigned int usec_per_tick = 1000;
|
||||
|
||||
/** Receive hook called by Mux driver. */
|
||||
static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg);
|
||||
|
||||
|
@ -126,7 +133,12 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
int unit_no = -1;
|
||||
ETHERCAT_PKT_DEV * pPktDev;
|
||||
|
||||
/* Make refrerece to packet device struct, keep track if the packet
|
||||
/* Get systick info, sysClkRateGet return ticks per second */
|
||||
usec_per_tick = USECS_PER_SEC / sysClkRateGet();
|
||||
/* Don't allow 0 since it is used in DIV */
|
||||
if(usec_per_tick == 0)
|
||||
usec_per_tick = 1;
|
||||
/* Make reference to packet device struct, keep track if the packet
|
||||
* device is the redundant or not.
|
||||
*/
|
||||
if (secondary)
|
||||
|
@ -139,14 +151,14 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
pPktDev = &(port->pktDev);
|
||||
pPktDev->redundant = 0;
|
||||
}
|
||||
|
||||
|
||||
/* Clear frame counters*/
|
||||
pPktDev->tx_count = 0;
|
||||
pPktDev->rx_count = 0;
|
||||
pPktDev->overrun_count = 0;
|
||||
|
||||
/* Create multi-thread support semaphores */
|
||||
port->sem_get_index = semBCreate(SEM_Q_FIFO, SEM_FULL);
|
||||
port->sem_get_index = semMCreate(SEM_Q_PRIORITY | SEM_INVERSION_SAFE);
|
||||
|
||||
/* Get the dev name and unit from ifname
|
||||
* We assume form gei1, fei0...
|
||||
|
@ -162,23 +174,32 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* Detach IP stack */
|
||||
//ipDetach(pktDev.unit,pktDev.name);
|
||||
|
||||
|
||||
pPktDev->port = port;
|
||||
|
||||
|
||||
/* Bind to mux driver for given interface, include ethercat driver pointer
|
||||
* as user reference
|
||||
*/
|
||||
/* Bind to mux */
|
||||
pPktDev->pCookie = muxBind(ifn, unit_no, mux_rx_callback, NULL, NULL, NULL, MUX_PROTO_SNARF, "ECAT SNARF", pPktDev);
|
||||
pPktDev->pCookie = muxBind(ifn,
|
||||
unit_no,
|
||||
mux_rx_callback,
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
MUX_PROTO_SNARF,
|
||||
"ECAT SNARF",
|
||||
pPktDev);
|
||||
|
||||
if (pPktDev->pCookie == NULL)
|
||||
{
|
||||
/* fail */
|
||||
NIC_LOGMSG("ecx_setupnic: muxBind init for gei: %d failed\n", unit_no, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
/* fail */
|
||||
NIC_LOGMSG("ecx_setupnic: muxBind init for gei: %d failed\n",
|
||||
unit_no, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
}
|
||||
|
||||
/* Get reference tp END obje */
|
||||
|
@ -186,11 +207,11 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
|
||||
if (port->pktDev.endObj == NULL)
|
||||
{
|
||||
/* fail */
|
||||
NIC_LOGMSG("error_hook: endFindByName failed, device gei: %d not found\n",
|
||||
unit_no, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
}
|
||||
/* fail */
|
||||
NIC_LOGMSG("error_hook: endFindByName failed, device gei: %d not found\n",
|
||||
unit_no, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
}
|
||||
|
||||
if (secondary)
|
||||
{
|
||||
|
@ -236,17 +257,17 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
/* Create mailboxes for each potential EtherCAT frame index */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
port->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
|
||||
if (port->msgQId[i] == MSG_Q_ID_NULL)
|
||||
{
|
||||
NIC_LOGMSG("ecx_setupnic: Failed to create MsgQ[%d]",
|
||||
i, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
}
|
||||
port->msgQId[i] = msgQCreate(1, sizeof(M_BLK_ID), MSG_Q_FIFO);
|
||||
if (port->msgQId[i] == MSG_Q_ID_NULL)
|
||||
{
|
||||
NIC_LOGMSG("ecx_setupnic: Failed to create MsgQ[%d]",
|
||||
i, 2, 3, 4, 5, 6);
|
||||
goto exit;
|
||||
}
|
||||
}
|
||||
ecx_clear_rxbufstat(&(port->rxbufstat[0]));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/* setup ethernet headers in tx buffers so we don't have to repeat it */
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
|
@ -254,9 +275,9 @@ int ecx_setupnic(ecx_portt *port, const char *ifname, int secondary)
|
|||
port->rxbufstat[i] = EC_BUF_EMPTY;
|
||||
}
|
||||
ec_setupheader(&(port->txbuf2));
|
||||
|
||||
|
||||
return 1;
|
||||
|
||||
|
||||
exit:
|
||||
|
||||
return 0;
|
||||
|
@ -271,20 +292,31 @@ int ecx_closenic(ecx_portt *port)
|
|||
{
|
||||
int i;
|
||||
ETHERCAT_PKT_DEV * pPktDev;
|
||||
M_BLK_ID trash_can;
|
||||
|
||||
pPktDev = &(port->pktDev);
|
||||
|
||||
for (i = 0; i < EC_MAXBUF; i++)
|
||||
{
|
||||
if (port->msgQId[i] != MSG_Q_ID_NULL)
|
||||
{
|
||||
msgQDelete(port->msgQId[i]);
|
||||
if (port->msgQId[i] != MSG_Q_ID_NULL)
|
||||
{
|
||||
if (msgQReceive(port->msgQId[i],
|
||||
(char *)&trash_can,
|
||||
sizeof(M_BLK_ID),
|
||||
NO_WAIT) != ERROR)
|
||||
{
|
||||
NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
|
||||
2, 3, 4, 5, 6);
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
msgQDelete(port->msgQId[i]);
|
||||
}
|
||||
}
|
||||
|
||||
if (pPktDev->pCookie != NULL)
|
||||
{
|
||||
muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
|
||||
muxUnbind(pPktDev->pCookie, MUX_PROTO_SNARF, mux_rx_callback);
|
||||
}
|
||||
|
||||
/* Clean redundant resources if available*/
|
||||
|
@ -295,6 +327,16 @@ int ecx_closenic(ecx_portt *port)
|
|||
{
|
||||
if (port->redport->msgQId[i] != MSG_Q_ID_NULL)
|
||||
{
|
||||
if (msgQReceive(port->redport->msgQId[i],
|
||||
(char *)&trash_can,
|
||||
sizeof(M_BLK_ID),
|
||||
NO_WAIT) != ERROR)
|
||||
{
|
||||
NIC_LOGMSG("ecx_closenic: idx %d MsgQ close\n", i,
|
||||
2, 3, 4, 5, 6);
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
msgQDelete(port->redport->msgQId[i]);
|
||||
}
|
||||
}
|
||||
|
@ -308,8 +350,8 @@ int ecx_closenic(ecx_portt *port)
|
|||
}
|
||||
|
||||
/** Fill buffer with ethernet header structure.
|
||||
* Destination MAC is allways broadcast.
|
||||
* Ethertype is allways ETH_P_ECAT.
|
||||
* Destination MAC is always broadcast.
|
||||
* Ethertype is always ETH_P_ECAT.
|
||||
* @param[out] p = buffer
|
||||
*/
|
||||
void ec_setupheader(void *p)
|
||||
|
@ -329,12 +371,10 @@ void ec_setupheader(void *p)
|
|||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
int idx;
|
||||
int cnt;
|
||||
MSG_Q_ID msgQId;
|
||||
M_BLK_ID trash_can;
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
semTake(port->sem_get_index, WAIT_FOREVER);
|
||||
|
||||
|
@ -356,27 +396,6 @@ int ecx_getindex(ecx_portt *port)
|
|||
}
|
||||
}
|
||||
port->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
|
||||
/* Clean up any abandoned frames */
|
||||
msgQId = port->msgQId[idx];
|
||||
if (msgQReceive(msgQId, (char *)&trash_can, sizeof(M_BLK_ID), NO_WAIT) == OK)
|
||||
{
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_ALLOC;
|
||||
/* Clean up any abandoned frames */
|
||||
msgQId = port->redport->msgQId[idx];
|
||||
if (msgQReceive(msgQId, (char *)&trash_can, sizeof(M_BLK_ID), NO_WAIT) == OK)
|
||||
{
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
}
|
||||
|
||||
port->lastidx = idx;
|
||||
|
||||
semGive(port->sem_get_index);
|
||||
|
@ -389,7 +408,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -398,35 +417,59 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
|
||||
/** Low level transmit buffer over mux layer 2 driver
|
||||
*
|
||||
* @param[in] pPktDev = packet device to send buffer over
|
||||
* @param[in] pPktDev = packet device to send buffer over
|
||||
* @param[in] idx = index in tx buffer array
|
||||
* @param[in] buf = buff to send
|
||||
* @param[in] len = bytes to send
|
||||
* @return driver send result
|
||||
*/
|
||||
static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, void * buf, int len)
|
||||
static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, uint8 idx, void * buf, int len)
|
||||
{
|
||||
STATUS status = OK;
|
||||
M_BLK_ID pPacket;
|
||||
int rval = 0;
|
||||
STATUS status = OK;
|
||||
M_BLK_ID pPacket = NULL;
|
||||
int rval = 0;
|
||||
END_OBJ *endObj = (END_OBJ *)pPktDev->endObj;
|
||||
MSG_Q_ID msgQId;
|
||||
|
||||
/* Allocate m_blk to send */
|
||||
if ((pPacket = netTupleGet(pPktDev->endObj->pNetPool,
|
||||
len,
|
||||
M_DONTWAIT,
|
||||
MT_DATA,
|
||||
TRUE)) == NULL)
|
||||
/* Clean up any abandoned frames and re-use the allocated buffer*/
|
||||
msgQId = pPktDev->port->msgQId[idx];
|
||||
if(msgQNumMsgs(msgQId) > 0)
|
||||
{
|
||||
NIC_LOGMSG("ec_outfram_send: Could not allocate MBLK memory!\n", 1, 2, 3, 4, 5, 6);
|
||||
return ERROR;
|
||||
pPktDev->abandoned_count++;
|
||||
NIC_LOGMSG("ec_outfram_send: idx %d MsgQ abandoned\n", idx,
|
||||
2, 3, 4, 5, 6);
|
||||
if (msgQReceive(msgQId,
|
||||
(char *)&pPacket,
|
||||
sizeof(M_BLK_ID),
|
||||
NO_WAIT) == ERROR)
|
||||
{
|
||||
pPacket = NULL;
|
||||
NIC_LOGMSG("ec_outfram_send: idx %d MsgQ mBlk handled by receiver\n", idx,
|
||||
2, 3, 4, 5, 6);
|
||||
}
|
||||
}
|
||||
|
||||
if (pPacket == NULL)
|
||||
{
|
||||
/* Allocate m_blk to send */
|
||||
if ((pPacket = netTupleGet(endObj->pNetPool,
|
||||
len,
|
||||
M_DONTWAIT,
|
||||
MT_DATA,
|
||||
TRUE)) == NULL)
|
||||
{
|
||||
NIC_LOGMSG("ec_outfram_send: Could not allocate MBLK memory!\n", 1, 2, 3, 4, 5, 6);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
pPacket->mBlkHdr.mLen = len;
|
||||
pPacket->mBlkHdr.mFlags |= M_HEADER;
|
||||
pPacket->mBlkHdr.mFlags |= M_PKTHDR;
|
||||
pPacket->mBlkHdr.mData = pPacket->pClBlk->clNode.pClBuf;
|
||||
pPacket->mBlkPktHdr.len = len;
|
||||
pPacket->mBlkPktHdr.len = pPacket->m_len;
|
||||
|
||||
netMblkFromBufCopy(pPacket, buf, 0, pPacket->mBlkHdr.mLen, M_DONTWAIT, NULL);
|
||||
status = muxTkSend(pPktDev->pCookie, pPacket, NULL, htons(ETH_P_ECAT), NULL);
|
||||
status = muxSend(endObj, pPacket);
|
||||
|
||||
if (status == OK)
|
||||
{
|
||||
|
@ -457,7 +500,7 @@ static int ec_outfram_send(ETHERCAT_PKT_DEV * pPktDev, void * buf, int len)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int rval = 0;
|
||||
ec_stackT *stack;
|
||||
|
@ -474,13 +517,17 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
pPktDev = &(port->redport->pktDev);
|
||||
}
|
||||
|
||||
rval = ec_outfram_send(pPktDev, (char*)(*stack->txbuf)[idx],
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = ec_outfram_send(pPktDev, idx, (char*)(*stack->txbuf)[idx],
|
||||
(*stack->txbuflength)[idx]);
|
||||
if (rval > 0)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
port->pktDev.tx_count++;
|
||||
}
|
||||
else
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -490,7 +537,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
|
@ -511,9 +558,13 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
/* rewrite MAC source address 1 to secondary */
|
||||
ehp->sa1 = htons(secMAC[1]);
|
||||
/* transmit over secondary interface */
|
||||
rval = ec_outfram_send(&(port->redport->pktDev), &(port->txbuf2), port->txbuflength2);
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
}
|
||||
rval = ec_outfram_send(&(port->redport->pktDev), idx, &(port->txbuf2), port->txbuflength2);
|
||||
if (rval <= 0)
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -521,93 +572,101 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
|
||||
/** Call back routine registered as hook with mux layer 2 driver
|
||||
* @param[in] pCookie = Mux cookie
|
||||
* @param[in] type = recived type
|
||||
* @param[in] type = received type
|
||||
* @param[in] pMblk = the received packet reference
|
||||
* @param[in] llHdrInfo = header info
|
||||
* @param[in] muxUserArg = assigned reference to packet device when init called
|
||||
* @return TRUE if frame was succesfully read and passed to MsgQ
|
||||
* @return TRUE if frame was successfully read and passed to MsgQ
|
||||
*/
|
||||
static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO *llHdrInfo, void *muxUserArg)
|
||||
{
|
||||
BOOL ret = FALSE;
|
||||
int idxf;
|
||||
uint8 idxf;
|
||||
ec_comt *ecp;
|
||||
ec_bufT * tempbuf;
|
||||
ecx_portt * port;
|
||||
MSG_Q_ID msgQId;
|
||||
ETHERCAT_PKT_DEV * pPktDev;
|
||||
int length;
|
||||
int bufstat;
|
||||
|
||||
/* check if it is an EtherCAT frame */
|
||||
if (type == ETH_P_ECAT)
|
||||
{
|
||||
length = pMblk->mBlkHdr.mLen;
|
||||
tempbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
|
||||
pPktDev = (ETHERCAT_PKT_DEV *)muxUserArg;
|
||||
port = pPktDev->port;
|
||||
length = pMblk->mBlkHdr.mLen;
|
||||
tempbuf = (ec_bufT *)pMblk->mBlkHdr.mData;
|
||||
pPktDev = (ETHERCAT_PKT_DEV *)muxUserArg;
|
||||
port = pPktDev->port;
|
||||
|
||||
/* Get ethercat frame header */
|
||||
ecp = (ec_comt*)&(*tempbuf)[ETH_HEADERSIZE];
|
||||
idxf = ecp->index;
|
||||
if (idxf >= EC_MAXBUF)
|
||||
{
|
||||
NIC_LOGMSG("mux_rx_callback: idx %d out of bounds\n", idxf,
|
||||
2, 3, 4, 5, 6);
|
||||
return ret;
|
||||
}
|
||||
/* Get ethercat frame header */
|
||||
ecp = (ec_comt*)&(*tempbuf)[ETH_HEADERSIZE];
|
||||
idxf = ecp->index;
|
||||
if (idxf >= EC_MAXBUF)
|
||||
{
|
||||
NIC_LOGMSG("mux_rx_callback: idx %d out of bounds\n", idxf,
|
||||
2, 3, 4, 5, 6);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Check if it is the redundant port or not */
|
||||
if (pPktDev->redundant == 1)
|
||||
{
|
||||
msgQId = port->redport->msgQId[idxf];
|
||||
}
|
||||
else
|
||||
{
|
||||
msgQId = port->msgQId[idxf];
|
||||
}
|
||||
/* Check if it is the redundant port or not */
|
||||
if (pPktDev->redundant == 1)
|
||||
{
|
||||
bufstat = port->redport->rxbufstat[idxf];
|
||||
msgQId = port->redport->msgQId[idxf];
|
||||
}
|
||||
else
|
||||
{
|
||||
bufstat = port->rxbufstat[idxf];
|
||||
msgQId = port->msgQId[idxf];
|
||||
}
|
||||
|
||||
if (length > 0)
|
||||
{
|
||||
/* Post the frame to the reqceive Q for the EtherCAT stack */
|
||||
STATUS status;
|
||||
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
|
||||
NO_WAIT, MSG_PRI_NORMAL);
|
||||
/* Check length and if someone expects the frame */
|
||||
if (length > 0 && bufstat == EC_BUF_TX)
|
||||
{
|
||||
/* Post the frame to the receive Q for the EtherCAT stack */
|
||||
STATUS status;
|
||||
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
|
||||
NO_WAIT, MSG_PRI_NORMAL);
|
||||
if (status == OK)
|
||||
{
|
||||
NIC_WVEVENT(ECAT_RECV_OK, (char *)&length, sizeof(length));
|
||||
ret = TRUE;
|
||||
}
|
||||
else if ((status == ERROR) && (errno == S_objLib_OBJ_UNAVAILABLE))
|
||||
{
|
||||
/* Try to empty the MSGQ since we for some strange reason
|
||||
* already have a frame in the MsqQ,
|
||||
* is it due to timeout when receiving?
|
||||
* We want the latest received frame in the buffer
|
||||
*/
|
||||
port->pktDev.overrun_count++;
|
||||
NIC_LOGMSG("mux_rx_callback: idx %d MsgQ overrun\n", idxf,
|
||||
2, 3, 4, 5, 6);
|
||||
M_BLK_ID trash_can;
|
||||
if (msgQReceive(msgQId,
|
||||
(char *)&trash_can,
|
||||
sizeof(M_BLK_ID),
|
||||
NO_WAIT) != ERROR)
|
||||
{
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
status = msgQSend(msgQId,
|
||||
(char *)&pMblk,
|
||||
sizeof(M_BLK_ID),
|
||||
NO_WAIT,
|
||||
MSG_PRI_NORMAL);
|
||||
if (status == OK)
|
||||
{
|
||||
NIC_WVEVENT(ECAT_RECV_OK, (char *)&length, sizeof(length));
|
||||
ret = TRUE;
|
||||
NIC_WVEVENT(ECAT_RECV_RETRY_OK, (char *)&length, sizeof(length));
|
||||
ret = TRUE;
|
||||
}
|
||||
else if ((status == ERROR) && (errno == S_objLib_OBJ_UNAVAILABLE))
|
||||
{
|
||||
/* Try to empty the MSGQ since we for some strange reason
|
||||
* already have a frame in the MsqQ,
|
||||
* is it due to timeout when receiving?
|
||||
* We want the latest received frame in the buffer
|
||||
*/
|
||||
port->pktDev.overrun_count++;
|
||||
NIC_LOGMSG("mux_rx_callback: idx %d MsgQ overrun\n", idxf,
|
||||
2, 3, 4, 5, 6);
|
||||
M_BLK_ID trash_can;
|
||||
if (msgQReceive(msgQId, (char *)&trash_can,
|
||||
sizeof(M_BLK_ID), NO_WAIT) == OK)
|
||||
{
|
||||
/* Free resources */
|
||||
netMblkClChainFree(trash_can);
|
||||
}
|
||||
|
||||
status = msgQSend(msgQId, (char *)&pMblk, sizeof(M_BLK_ID),
|
||||
NO_WAIT, MSG_PRI_NORMAL);
|
||||
if (status == OK)
|
||||
{
|
||||
NIC_WVEVENT(ECAT_RECV_RETRY_OK, (char *)&length, sizeof(length));
|
||||
ret = TRUE;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
NIC_WVEVENT(ECAT_RECV_FAILED, (char *)&length, sizeof(length));
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
NIC_WVEVENT(ECAT_RECV_FAILED, (char *)&length, sizeof(length));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
|
@ -619,11 +678,11 @@ static int mux_rx_callback(void* pCookie, long type, M_BLK_ID pMblk, LL_HDR_INFO
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return >0 if frame is available and read
|
||||
*/
|
||||
static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID * pMblk, int timeout)
|
||||
static int ecx_recvpkt(ecx_portt *port, uint8 idx, int stacknumber, M_BLK_ID * pMblk, int timeout)
|
||||
{
|
||||
int bytesrx = 0;
|
||||
MSG_Q_ID msgQId;
|
||||
int tick_timeout = max((timeout / 1000), 1);
|
||||
int tick_timeout = max((timeout / usec_per_tick), 1);
|
||||
|
||||
if (stacknumber == 1)
|
||||
{
|
||||
|
@ -660,7 +719,7 @@ static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID * pMb
|
|||
* task tNet0 (default), tNet0 fetch what frame index and store a reference to the
|
||||
* received frame in matching MsgQ. The stack user tasks fetch the frame
|
||||
* reference and copies the frame the the RX buffer, when done it free
|
||||
* the frame buffer alloctaed by the Mux.
|
||||
* the frame buffer allocated by the Mux.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] idx = requested index of frame
|
||||
|
@ -669,7 +728,7 @@ static int ecx_recvpkt(ecx_portt *port, int idx, int stacknumber, M_BLK_ID * pMb
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber, int timeout)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber, int timeout)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
|
@ -733,7 +792,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber, int timeout)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer, int timeout)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer, int timeout)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
|
@ -766,10 +825,10 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer, int
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
@ -822,7 +881,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer, int
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
@ -833,7 +892,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -845,7 +904,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
@ -861,7 +920,7 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
|
@ -884,37 +943,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber, int timeout)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber, timeout);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -17,18 +17,18 @@ extern "C"
|
|||
#endif
|
||||
|
||||
#include <vxWorks.h>
|
||||
#include <muxLib.h>
|
||||
|
||||
/** structure to connect EtherCAT stack and VxWorks device */
|
||||
typedef struct ETHERCAT_PKT_DEV
|
||||
{
|
||||
struct ecx_port *port;
|
||||
void *pCookie;
|
||||
END_OBJ *endObj;
|
||||
void *endObj;
|
||||
UINT32 redundant;
|
||||
UINT32 tx_count;
|
||||
UINT32 rx_count;
|
||||
UINT32 overrun_count;
|
||||
UINT32 abandoned_count;
|
||||
}ETHERCAT_PKT_DEV;
|
||||
|
||||
/** pointer structure to Tx and Rx stacks */
|
||||
|
@ -78,14 +78,14 @@ typedef struct ecx_port
|
|||
int rxsa[EC_MAXBUF];
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -105,23 +105,23 @@ extern ecx_redportt ecx_redport;
|
|||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int sock);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -51,7 +51,7 @@ enum
|
|||
{
|
||||
/** No redundancy, single NIC mode */
|
||||
ECT_RED_NONE,
|
||||
/** Double redundant NIC connecetion */
|
||||
/** Double redundant NIC connection */
|
||||
ECT_RED_DOUBLE
|
||||
};
|
||||
|
||||
|
@ -60,7 +60,7 @@ enum
|
|||
* EtherCAT does not care about MAC addressing, but it is used here to
|
||||
* differentiate the route the packet traverses through the EtherCAT
|
||||
* segment. This is needed to fund out the packet flow in redundant
|
||||
* confihurations. */
|
||||
* configurations. */
|
||||
const uint16 priMAC[3] = { 0x0101, 0x0101, 0x0101 };
|
||||
/** Secondary source MAC address used for EtherCAT. */
|
||||
const uint16 secMAC[3] = { 0x0404, 0x0404, 0x0404 };
|
||||
|
@ -202,10 +202,10 @@ void ec_setupheader(void *p)
|
|||
* @param[in] port = port context struct
|
||||
* @return new index.
|
||||
*/
|
||||
int ecx_getindex(ecx_portt *port)
|
||||
uint8 ecx_getindex(ecx_portt *port)
|
||||
{
|
||||
int idx;
|
||||
int cnt;
|
||||
uint8 idx;
|
||||
uint8 cnt;
|
||||
|
||||
EnterCriticalSection(&(port->getindex_mutex));
|
||||
|
||||
|
@ -241,7 +241,7 @@ int ecx_getindex(ecx_portt *port)
|
|||
* @param[in] idx = index in buffer array
|
||||
* @param[in] bufstat = status to set
|
||||
*/
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat)
|
||||
{
|
||||
port->rxbufstat[idx] = bufstat;
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
|
@ -254,7 +254,7 @@ void ecx_setbufstat(ecx_portt *port, int idx, int bufstat)
|
|||
* @param[in] stacknumber = 0=Primary 1=Secondary stack
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
int lp, rval;
|
||||
ec_stackT *stack;
|
||||
|
@ -268,8 +268,12 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
stack = &(port->redport->stack);
|
||||
}
|
||||
lp = (*stack->txbuflength)[idx];
|
||||
rval = pcap_sendpacket(*stack->sock, (*stack->txbuf)[idx], lp);
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_TX;
|
||||
rval = pcap_sendpacket(*stack->sock, (*stack->txbuf)[idx], lp);
|
||||
if (rval == PCAP_ERROR)
|
||||
{
|
||||
(*stack->rxbufstat)[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
|
||||
return rval;
|
||||
}
|
||||
|
@ -279,7 +283,7 @@ int ecx_outframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @param[in] idx = index in tx buffer array
|
||||
* @return socket send result
|
||||
*/
|
||||
int ecx_outframe_red(ecx_portt *port, int idx)
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
ec_etherheadert *ehp;
|
||||
|
@ -301,9 +305,12 @@ int ecx_outframe_red(ecx_portt *port, int idx)
|
|||
/* rewrite MAC source address 1 to secondary */
|
||||
ehp->sa1 = htons(secMAC[1]);
|
||||
/* transmit over secondary socket */
|
||||
pcap_sendpacket(port->redport->sockhandle, (u_char const *)&(port->txbuf2), port->txbuflength2);
|
||||
LeaveCriticalSection( &(port->tx_mutex) );
|
||||
port->redport->rxbufstat[idx] = EC_BUF_TX;
|
||||
if (pcap_sendpacket(port->redport->sockhandle, (u_char const *)&(port->txbuf2), port->txbuflength2) == PCAP_ERROR)
|
||||
{
|
||||
port->redport->rxbufstat[idx] = EC_BUF_EMPTY;
|
||||
}
|
||||
LeaveCriticalSection( &(port->tx_mutex) );
|
||||
}
|
||||
|
||||
return rval;
|
||||
|
@ -351,7 +358,7 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
/** Non blocking receive frame function. Uses RX buffer and index to combine
|
||||
* read frame with transmitted frame. To compensate for received frames that
|
||||
* are out-of-order all frames are stored in their respective indexed buffer.
|
||||
* If a frame was placed in the buffer previously, the function retreives it
|
||||
* If a frame was placed in the buffer previously, the function retrieves it
|
||||
* from that buffer index without calling ec_recvpkt. If the requested index
|
||||
* is not already in the buffer it calls ec_recvpkt to fetch it. There are
|
||||
* three options now, 1 no frame read, so exit. 2 frame read but other
|
||||
|
@ -364,11 +371,11 @@ static int ecx_recvpkt(ecx_portt *port, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME or EC_OTHERFRAME.
|
||||
*/
|
||||
int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
||||
int ecx_inframe(ecx_portt *port, uint8 idx, int stacknumber)
|
||||
{
|
||||
uint16 l;
|
||||
int rval;
|
||||
int idxf;
|
||||
uint8 idxf;
|
||||
ec_etherheadert *ehp;
|
||||
ec_comt *ecp;
|
||||
ec_stackT *stack;
|
||||
|
@ -407,7 +414,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
ecp =(ec_comt*)(&(*stack->tempbuf)[ETH_HEADERSIZE]);
|
||||
l = etohs(ecp->elength) & 0x0fff;
|
||||
idxf = ecp->index;
|
||||
/* found index equals reqested index ? */
|
||||
/* found index equals requested index ? */
|
||||
if (idxf == idx)
|
||||
{
|
||||
/* yes, put it in the buffer array (strip ethernet header) */
|
||||
|
@ -433,7 +440,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* strange things happend */
|
||||
/* strange things happened */
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -442,7 +449,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
|
||||
}
|
||||
|
||||
/* WKC if mathing frame found */
|
||||
/* WKC if matching frame found */
|
||||
return rval;
|
||||
}
|
||||
|
||||
|
@ -458,7 +465,7 @@ int ecx_inframe(ecx_portt *port, int idx, int stacknumber)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
||||
static int ecx_waitinframe_red(ecx_portt *port, uint8 idx, osal_timert *timer)
|
||||
{
|
||||
osal_timert timer2;
|
||||
int wkc = EC_NOFRAME;
|
||||
|
@ -485,10 +492,10 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
/* only do redundant functions when in redundant mode */
|
||||
if (port->redstate != ECT_RED_NONE)
|
||||
{
|
||||
/* primrx if the reveived MAC source on primary socket */
|
||||
/* primrx if the received MAC source on primary socket */
|
||||
primrx = 0;
|
||||
if (wkc > EC_NOFRAME) primrx = port->rxsa[idx];
|
||||
/* secrx if the reveived MAC source on psecondary socket */
|
||||
/* secrx if the received MAC source on psecondary socket */
|
||||
secrx = 0;
|
||||
if (wkc2 > EC_NOFRAME) secrx = port->redport->rxsa[idx];
|
||||
|
||||
|
@ -541,7 +548,7 @@ static int ecx_waitinframe_red(ecx_portt *port, int idx, osal_timert *timer)
|
|||
* @return Workcounter if a frame is found with corresponding index, otherwise
|
||||
* EC_NOFRAME.
|
||||
*/
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc;
|
||||
osal_timert timer;
|
||||
|
@ -552,7 +559,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
return wkc;
|
||||
}
|
||||
|
||||
/** Blocking send and recieve frame function. Used for non processdata frames.
|
||||
/** Blocking send and receive frame function. Used for non processdata frames.
|
||||
* A datagram is build into a frame and transmitted via this function. It waits
|
||||
* for an answer and returns the workcounter. The function retries if time is
|
||||
* left and the result is WKC=0 or no frame received.
|
||||
|
@ -564,7 +571,7 @@ int ecx_waitinframe(ecx_portt *port, int idx, int timeout)
|
|||
* @param[in] timeout = timeout in us
|
||||
* @return Workcounter or EC_NOFRAME
|
||||
*/
|
||||
int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx, int timeout)
|
||||
{
|
||||
int wkc = EC_NOFRAME;
|
||||
osal_timert timer1, timer2;
|
||||
|
@ -580,18 +587,13 @@ int ecx_srconfirm(ecx_portt *port, int idx, int timeout)
|
|||
}
|
||||
else
|
||||
{
|
||||
/* normally use partial timout for rx */
|
||||
/* normally use partial timeout for rx */
|
||||
osal_timer_start (&timer2, EC_TIMEOUTRET);
|
||||
}
|
||||
/* get frame from primary or if in redundant mode possibly from secondary */
|
||||
wkc = ecx_waitinframe_red(port, idx, &timer2);
|
||||
/* wait for answer with WKC>=0 or otherwise retry until timeout */
|
||||
} while ((wkc <= EC_NOFRAME) && !osal_timer_is_expired (&timer1));
|
||||
/* if nothing received, clear buffer index status so it can be used again */
|
||||
if (wkc <= EC_NOFRAME)
|
||||
{
|
||||
ecx_setbufstat(port, idx, EC_BUF_EMPTY);
|
||||
}
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
@ -609,37 +611,37 @@ int ec_closenic(void)
|
|||
return ecx_closenic(&ecx_port);
|
||||
}
|
||||
|
||||
int ec_getindex(void)
|
||||
uint8 ec_getindex(void)
|
||||
{
|
||||
return ecx_getindex(&ecx_port);
|
||||
}
|
||||
|
||||
void ec_setbufstat(int idx, int bufstat)
|
||||
void ec_setbufstat(uint8 idx, int bufstat)
|
||||
{
|
||||
ecx_setbufstat(&ecx_port, idx, bufstat);
|
||||
}
|
||||
|
||||
int ec_outframe(int idx, int stacknumber)
|
||||
int ec_outframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_outframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_outframe_red(int idx)
|
||||
int ec_outframe_red(uint8 idx)
|
||||
{
|
||||
return ecx_outframe_red(&ecx_port, idx);
|
||||
}
|
||||
|
||||
int ec_inframe(int idx, int stacknumber)
|
||||
int ec_inframe(uint8 idx, int stacknumber)
|
||||
{
|
||||
return ecx_inframe(&ecx_port, idx, stacknumber);
|
||||
}
|
||||
|
||||
int ec_waitinframe(int idx, int timeout)
|
||||
int ec_waitinframe(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_waitinframe(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
||||
int ec_srconfirm(int idx, int timeout)
|
||||
int ec_srconfirm(uint8 idx, int timeout)
|
||||
{
|
||||
return ecx_srconfirm(&ecx_port, idx, timeout);
|
||||
}
|
||||
|
|
|
@ -72,14 +72,14 @@ typedef struct
|
|||
int tempinbufs;
|
||||
/** transmit buffers */
|
||||
ec_bufT txbuf[EC_MAXBUF];
|
||||
/** transmit buffer lenghts */
|
||||
/** transmit buffer lengths */
|
||||
int txbuflength[EC_MAXBUF];
|
||||
/** temporary tx buffer */
|
||||
ec_bufT txbuf2;
|
||||
/** temporary tx buffer length */
|
||||
int txbuflength2;
|
||||
/** last used frame index */
|
||||
int lastidx;
|
||||
uint8 lastidx;
|
||||
/** current redundancy state */
|
||||
int redstate;
|
||||
/** pointer to redundancy port and buffers */
|
||||
|
@ -98,23 +98,23 @@ extern ecx_redportt ecx_redport;
|
|||
|
||||
int ec_setupnic(const char * ifname, int secondary);
|
||||
int ec_closenic(void);
|
||||
void ec_setbufstat(int idx, int bufstat);
|
||||
int ec_getindex(void);
|
||||
int ec_outframe(int idx, int sock);
|
||||
int ec_outframe_red(int idx);
|
||||
int ec_waitinframe(int idx, int timeout);
|
||||
int ec_srconfirm(int idx,int timeout);
|
||||
void ec_setbufstat(uint8 idx, int bufstat);
|
||||
uint8 ec_getindex(void);
|
||||
int ec_outframe(uint8 idx, int sock);
|
||||
int ec_outframe_red(uint8 idx);
|
||||
int ec_waitinframe(uint8 idx, int timeout);
|
||||
int ec_srconfirm(uint8 idx,int timeout);
|
||||
#endif
|
||||
|
||||
void ec_setupheader(void *p);
|
||||
int ecx_setupnic(ecx_portt *port, const char * ifname, int secondary);
|
||||
int ecx_closenic(ecx_portt *port);
|
||||
void ecx_setbufstat(ecx_portt *port, int idx, int bufstat);
|
||||
int ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, int idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, int idx);
|
||||
int ecx_waitinframe(ecx_portt *port, int idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, int idx,int timeout);
|
||||
void ecx_setbufstat(ecx_portt *port, uint8 idx, int bufstat);
|
||||
uint8 ecx_getindex(ecx_portt *port);
|
||||
int ecx_outframe(ecx_portt *port, uint8 idx, int sock);
|
||||
int ecx_outframe_red(ecx_portt *port, uint8 idx);
|
||||
int ecx_waitinframe(ecx_portt *port, uint8 idx, int timeout);
|
||||
int ecx_srconfirm(ecx_portt *port, uint8 idx,int timeout);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -42,7 +42,6 @@ ec_adaptert * oshw_find_adapters (void)
|
|||
ec_adaptert * prev_adapter;
|
||||
ec_adaptert * ret_adapter = NULL;
|
||||
char errbuf[PCAP_ERRBUF_SIZE];
|
||||
size_t string_len;
|
||||
|
||||
/* find all devices */
|
||||
if (pcap_findalldevs(&alldevs, errbuf) == -1)
|
||||
|
@ -51,7 +50,7 @@ ec_adaptert * oshw_find_adapters (void)
|
|||
return (NULL);
|
||||
}
|
||||
/* Iterate all devices and create a local copy holding the name and
|
||||
* decsription.
|
||||
* description.
|
||||
*/
|
||||
for(d= alldevs; d != NULL; d= d->next)
|
||||
{
|
||||
|
@ -69,17 +68,12 @@ ec_adaptert * oshw_find_adapters (void)
|
|||
ret_adapter = adapter;
|
||||
}
|
||||
|
||||
/* fetch description and name of the divice from libpcap */
|
||||
/* fetch description and name of the device from libpcap */
|
||||
adapter->next = NULL;
|
||||
if (d->name)
|
||||
{
|
||||
string_len = strlen(d->name);
|
||||
if (string_len > (EC_MAXLEN_ADAPTERNAME - 1))
|
||||
{
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->name, d->name,string_len);
|
||||
adapter->name[string_len] = '\0';
|
||||
strncpy(adapter->name, d->name, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->name[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -87,13 +81,8 @@ ec_adaptert * oshw_find_adapters (void)
|
|||
}
|
||||
if (d->description)
|
||||
{
|
||||
string_len = strlen(d->description);
|
||||
if (string_len > (EC_MAXLEN_ADAPTERNAME - 1))
|
||||
{
|
||||
string_len = EC_MAXLEN_ADAPTERNAME - 1;
|
||||
}
|
||||
strncpy(adapter->desc, d->description,string_len);
|
||||
adapter->desc[string_len] = '\0';
|
||||
strncpy(adapter->desc, d->description, EC_MAXLEN_ADAPTERNAME);
|
||||
adapter->desc[EC_MAXLEN_ADAPTERNAME-1] = '\0';
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -115,7 +104,7 @@ ec_adaptert * oshw_find_adapters (void)
|
|||
void oshw_free_adapters (ec_adaptert * adapter)
|
||||
{
|
||||
ec_adaptert * next_adapter;
|
||||
/* Iterate the linked list and free all elemnts holding
|
||||
/* Iterate the linked list and free all elements holding
|
||||
* adapter information
|
||||
*/
|
||||
if(adapter)
|
||||
|
|
|
@ -284,7 +284,7 @@ struct _PACKET_OID_DATA {
|
|||
ULONG Oid; ///< OID code. See the Microsoft DDK documentation or the file ntddndis.h
|
||||
///< for a complete list of valid codes.
|
||||
ULONG Length; ///< Length of the data field
|
||||
UCHAR Data[1]; ///< variable-lenght field that contains the information passed to or received
|
||||
UCHAR Data[1]; ///< variable-length field that contains the information passed to or received
|
||||
///< from the adapter.
|
||||
};
|
||||
typedef struct _PACKET_OID_DATA PACKET_OID_DATA, *PPACKET_OID_DATA;
|
||||
|
|
|
@ -395,7 +395,7 @@ struct pcap_samp
|
|||
|
||||
|
||||
|
||||
//! Maximum lenght of an host name (needed for the RPCAP active mode)
|
||||
//! Maximum length of an host name (needed for the RPCAP active mode)
|
||||
#define RPCAP_HOSTLIST_SIZE 1024
|
||||
|
||||
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include "ethercatcoe.h"
|
||||
#include "ethercatfoe.h"
|
||||
#include "ethercatsoe.h"
|
||||
#include "ethercateoe.h"
|
||||
#include "ethercatconfig.h"
|
||||
#include "ethercatprint.h"
|
||||
|
||||
|
|
|
@ -103,7 +103,7 @@ int ecx_setupdatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, uint16
|
|||
* @param[in] data = databuffer to be copied in datagram
|
||||
* @return Offset to data in rx frame, usefull to retrieve data after RX.
|
||||
*/
|
||||
int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data)
|
||||
uint16 ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data)
|
||||
{
|
||||
ec_comt *datagramP;
|
||||
uint8 *frameP;
|
||||
|
@ -111,7 +111,7 @@ int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean
|
|||
|
||||
frameP = frame;
|
||||
/* copy previous frame size */
|
||||
prevlength = port->txbuflength[idx];
|
||||
prevlength = (uint16)port->txbuflength[idx];
|
||||
datagramP = (ec_comt*)&frameP[ETH_HEADERSIZE];
|
||||
/* add new datagram to ethernet frame size */
|
||||
datagramP->elength = htoes( etohs(datagramP->elength) + EC_HEADERSIZE + length );
|
||||
|
@ -207,7 +207,7 @@ int ecx_BRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data,
|
|||
/** APRD "auto increment address read" primitive. Blocking.
|
||||
*
|
||||
* @param[in] port = port context struct
|
||||
* @param[in] ADP = Address Position, each slave ++, slave that has 0 excecutes
|
||||
* @param[in] ADP = Address Position, each slave ++, slave that has 0 executes
|
||||
* @param[in] ADO = Address Offset, slave memory address
|
||||
* @param[in] length = length of databuffer
|
||||
* @param[out] data = databuffer to put slave data in
|
||||
|
@ -541,7 +541,7 @@ int ec_setupdatagram(void *frame, uint8 com, uint8 idx, uint16 ADP, uint16 ADO,
|
|||
return ecx_setupdatagram (&ecx_port, frame, com, idx, ADP, ADO, length, data);
|
||||
}
|
||||
|
||||
int ec_adddatagram (void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data)
|
||||
uint16 ec_adddatagram (void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data)
|
||||
{
|
||||
return ecx_adddatagram (&ecx_port, frame, com, idx, more, ADP, ADO, length, data);
|
||||
}
|
||||
|
|
|
@ -17,7 +17,7 @@ extern "C"
|
|||
#endif
|
||||
|
||||
int ecx_setupdatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
int ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
uint16 ecx_adddatagram(ecx_portt *port, void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
int ecx_BWR(ecx_portt *port, uint16 ADP,uint16 ADO,uint16 length,void *data,int timeout);
|
||||
int ecx_BRD(ecx_portt *port, uint16 ADP,uint16 ADO,uint16 length,void *data,int timeout);
|
||||
int ecx_APRD(ecx_portt *port, uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout);
|
||||
|
@ -37,7 +37,7 @@ int ecx_LRWDC(ecx_portt *port, uint32 LogAdr, uint16 length, void *data, uint16
|
|||
|
||||
#ifdef EC_VER1
|
||||
int ec_setupdatagram(void *frame, uint8 com, uint8 idx, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
int ec_adddatagram(void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
uint16 ec_adddatagram(void *frame, uint8 com, uint8 idx, boolean more, uint16 ADP, uint16 ADO, uint16 length, void *data);
|
||||
int ec_BWR(uint16 ADP,uint16 ADO,uint16 length,void *data,int timeout);
|
||||
int ec_BRD(uint16 ADP,uint16 ADO,uint16 length,void *data,int timeout);
|
||||
int ec_APRD(uint16 ADP, uint16 ADO, uint16 length, void *data, int timeout);
|
||||
|
|
|
@ -131,7 +131,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
boolean NotLast;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aSDOp = (ec_SDOt *)&MbxIn;
|
||||
|
@ -142,7 +142,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOREQ << 12)); /* number 9bits service upper 4 bits (SDO request) */
|
||||
if (CA)
|
||||
{
|
||||
|
@ -218,7 +218,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
SDOp->MbxHeader.priority = 0x00;
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOREQ << 12)); /* number 9bits service upper 4 bits (SDO request) */
|
||||
SDOp->Command = ECT_SDO_SEG_UP_REQ + toggle; /* segment upload request */
|
||||
SDOp->Index = htoes(index);
|
||||
|
@ -226,7 +226,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
SDOp->ldata[0] = 0;
|
||||
/* send segmented upload request to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
/* is mailbox transfered to slave ? */
|
||||
/* is mailbox transferred to slave ? */
|
||||
if (wkc > 0)
|
||||
{
|
||||
ec_clearmbx(&MbxIn);
|
||||
|
@ -246,7 +246,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
{ /* last segment */
|
||||
NotLast = FALSE;
|
||||
if (Framedatasize == 7)
|
||||
/* substract unused bytes from frame */
|
||||
/* subtract unused bytes from frame */
|
||||
Framedatasize = Framedatasize - ((aSDOp->Command & 0x0e) >> 1);
|
||||
/* copy to parameter buffer */
|
||||
memcpy(hp, &(aSDOp->Index), Framedatasize);
|
||||
|
@ -258,7 +258,7 @@ int ecx_SDOread(ecx_contextt *context, uint16 slave, uint16 index, uint8 subinde
|
|||
/* increment buffer pointer */
|
||||
hp += Framedatasize;
|
||||
}
|
||||
/* update parametersize */
|
||||
/* update parameter size */
|
||||
*psize += Framedatasize;
|
||||
}
|
||||
/* unexpected frame returned from slave */
|
||||
|
@ -331,15 +331,14 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
boolean CA, int psize, void *p, int Timeout)
|
||||
{
|
||||
ec_SDOt *SDOp, *aSDOp;
|
||||
int wkc, maxdata;
|
||||
int wkc, maxdata, framedatasize;
|
||||
ec_mbxbuft MbxIn, MbxOut;
|
||||
uint8 cnt, toggle;
|
||||
uint16 framedatasize;
|
||||
boolean NotLast;
|
||||
uint8 *hp;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, Slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aSDOp = (ec_SDOt *)&MbxIn;
|
||||
|
@ -354,7 +353,7 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
/* get new mailbox counter, used for session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOREQ << 12)); /* number 9bits service upper 4 bits */
|
||||
SDOp->Command = ECT_SDO_DOWN_EXP | (((4 - psize) << 2) & 0x0c); /* expedited SDO download transfer */
|
||||
SDOp->Index = htoes(Index);
|
||||
|
@ -404,13 +403,13 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
framedatasize = maxdata; /* segmented transfer needed */
|
||||
NotLast = TRUE;
|
||||
}
|
||||
SDOp->MbxHeader.length = htoes(0x0a + framedatasize);
|
||||
SDOp->MbxHeader.length = htoes((uint16)(0x0a + framedatasize));
|
||||
SDOp->MbxHeader.address = htoes(0x0000);
|
||||
SDOp->MbxHeader.priority = 0x00;
|
||||
/* get new mailbox counter, used for session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOREQ << 12)); /* number 9bits service upper 4 bits */
|
||||
if (CA)
|
||||
{
|
||||
|
@ -466,18 +465,18 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
if (!NotLast && (framedatasize < 7))
|
||||
{
|
||||
SDOp->MbxHeader.length = htoes(0x0a); /* minimum size */
|
||||
SDOp->Command = 0x01 + ((7 - framedatasize) << 1); /* last segment reduced octets */
|
||||
SDOp->Command = (uint8)(0x01 + ((7 - framedatasize) << 1)); /* last segment reduced octets */
|
||||
}
|
||||
else
|
||||
{
|
||||
SDOp->MbxHeader.length = htoes(framedatasize + 3); /* data + 2 CoE + 1 SDO */
|
||||
SDOp->MbxHeader.length = htoes((uint16)(framedatasize + 3)); /* data + 2 CoE + 1 SDO */
|
||||
}
|
||||
SDOp->MbxHeader.address = htoes(0x0000);
|
||||
SDOp->MbxHeader.priority = 0x00;
|
||||
/* get new mailbox counter value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOREQ << 12)); /* number 9bits service upper 4 bits (SDO request) */
|
||||
SDOp->Command = SDOp->Command + toggle; /* add toggle bit to command byte */
|
||||
/* copy parameter data to mailbox */
|
||||
|
@ -552,13 +551,12 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
int ecx_RxPDO(ecx_contextt *context, uint16 Slave, uint16 RxPDOnumber, int psize, void *p)
|
||||
{
|
||||
ec_SDOt *SDOp;
|
||||
int wkc, maxdata;
|
||||
int wkc, maxdata, framedatasize;
|
||||
ec_mbxbuft MbxIn, MbxOut;
|
||||
uint8 cnt;
|
||||
uint16 framedatasize;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, Slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
SDOp = (ec_SDOt *)&MbxOut;
|
||||
|
@ -568,13 +566,13 @@ int ecx_RxPDO(ecx_contextt *context, uint16 Slave, uint16 RxPDOnumber, int psize
|
|||
{
|
||||
framedatasize = maxdata; /* limit transfer */
|
||||
}
|
||||
SDOp->MbxHeader.length = htoes(0x02 + framedatasize);
|
||||
SDOp->MbxHeader.length = htoes((uint16)(0x02 + framedatasize));
|
||||
SDOp->MbxHeader.address = htoes(0x0000);
|
||||
SDOp->MbxHeader.priority = 0x00;
|
||||
/* get new mailbox counter, used for session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes((RxPDOnumber & 0x01ff) + (ECT_COES_RXPDO << 12)); /* number 9bits service upper 4 bits */
|
||||
/* copy PDO data to mailbox */
|
||||
memcpy(&SDOp->Command, p, framedatasize);
|
||||
|
@ -605,7 +603,7 @@ int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psi
|
|||
uint16 framedatasize;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aSDOp = (ec_SDOt *)&MbxIn;
|
||||
|
@ -616,7 +614,7 @@ int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psi
|
|||
/* get new mailbox counter, used for session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes((TxPDOnumber & 0x01ff) + (ECT_COES_TXPDO_RR << 12)); /* number 9bits service upper 4 bits */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
if (wkc > 0)
|
||||
|
@ -672,12 +670,13 @@ int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psi
|
|||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
*/
|
||||
int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
uint32 ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
||||
{
|
||||
uint16 idxloop, nidx, subidxloop, rdat, idx, subidx;
|
||||
uint8 subcnt;
|
||||
int wkc, bsize = 0, rdl;
|
||||
int wkc, rdl;
|
||||
int32 rdat2;
|
||||
uint32 bsize = 0;
|
||||
|
||||
rdl = sizeof(rdat); rdat = 0;
|
||||
/* read PDO assign subindex 0 ( = number of PDO's) */
|
||||
|
@ -696,7 +695,7 @@ int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
|||
/* read PDO assign */
|
||||
wkc = ecx_SDOread(context, Slave, PDOassign, (uint8)idxloop, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
|
||||
/* result is index of PDO */
|
||||
idx = etohl(rdat);
|
||||
idx = etohs(rdat);
|
||||
if (idx > 0)
|
||||
{
|
||||
rdl = sizeof(subcnt); subcnt = 0;
|
||||
|
@ -737,11 +736,12 @@ int ecx_readPDOassign(ecx_contextt *context, uint16 Slave, uint16 PDOassign)
|
|||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
*/
|
||||
int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, int Thread_n,
|
||||
uint32 ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, int Thread_n,
|
||||
uint16 PDOassign)
|
||||
{
|
||||
uint16 idxloop, nidx, subidxloop, idx, subidx;
|
||||
int wkc, bsize = 0, rdl;
|
||||
int wkc, rdl;
|
||||
uint32 bsize = 0;
|
||||
|
||||
/* find maximum size of PDOassign buffer */
|
||||
rdl = sizeof(ec_PDOassignt);
|
||||
|
@ -805,14 +805,14 @@ int ecx_readPDOassignCA(ecx_contextt *context, uint16 Slave, int Thread_n,
|
|||
* @param[in] Slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
* @return >0 if mapping successful.
|
||||
*/
|
||||
int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
||||
int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
int wkc, rdl;
|
||||
int retVal = 0;
|
||||
uint8 nSM, iSM, tSM;
|
||||
int Tsize;
|
||||
uint32 Tsize;
|
||||
uint8 SMt_bug_add;
|
||||
|
||||
*Isize = 0;
|
||||
|
@ -868,7 +868,7 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
|||
/* if a mapping is found */
|
||||
if (Tsize)
|
||||
{
|
||||
context->slavelist[Slave].SM[iSM].SMlength = htoes((Tsize + 7) / 8);
|
||||
context->slavelist[Slave].SM[iSM].SMlength = htoes((uint16)((Tsize + 7) / 8));
|
||||
if (tSM == 3)
|
||||
{
|
||||
/* we are doing outputs */
|
||||
|
@ -905,14 +905,14 @@ int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize)
|
|||
* @param[in] Thread_n = Calling thread index
|
||||
* @param[out] Osize = Size in bits of output mapping (rxPDO) found
|
||||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
* @return >0 if mapping successful.
|
||||
*/
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, int *Osize, int *Isize)
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
int wkc, rdl;
|
||||
int retVal = 0;
|
||||
uint8 nSM, iSM, tSM;
|
||||
int Tsize;
|
||||
uint32 Tsize;
|
||||
uint8 SMt_bug_add;
|
||||
|
||||
*Isize = 0;
|
||||
|
@ -964,7 +964,7 @@ int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, int *Osi
|
|||
/* if a mapping is found */
|
||||
if (Tsize)
|
||||
{
|
||||
context->slavelist[Slave].SM[iSM].SMlength = htoes((Tsize + 7) / 8);
|
||||
context->slavelist[Slave].SM[iSM].SMlength = htoes((uint16)((Tsize + 7) / 8));
|
||||
if (tSM == 3)
|
||||
{
|
||||
/* we are doing outputs */
|
||||
|
@ -1019,7 +1019,7 @@ int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist)
|
|||
/* Get new mailbox counter value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOINFO << 12)); /* number 9bits service upper 4 bits */
|
||||
SDOp->Opcode = ECT_GET_ODLIST_REQ; /* get object description list request */
|
||||
SDOp->Reserved = 0;
|
||||
|
@ -1139,7 +1139,7 @@ int ecx_readODdescription(ecx_contextt *context, uint16 Item, ec_ODlistt *pODlis
|
|||
/* Get new mailbox counter value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOINFO << 12)); /* number 9bits service upper 4 bits */
|
||||
SDOp->Opcode = ECT_GET_OD_REQ; /* get object description request */
|
||||
SDOp->Reserved = 0;
|
||||
|
@ -1224,7 +1224,7 @@ int ecx_readOEsingle(ecx_contextt *context, uint16 Item, uint8 SubI, ec_ODlistt
|
|||
/* Get new mailbox counter value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[Slave].mbx_cnt);
|
||||
context->slavelist[Slave].mbx_cnt = cnt;
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + (cnt << 4); /* CoE */
|
||||
SDOp->MbxHeader.mbxtype = ECT_MBXT_COE + MBX_HDR_SET_CNT(cnt); /* CoE */
|
||||
SDOp->CANOpen = htoes(0x000 + (ECT_COES_SDOINFO << 12)); /* number 9bits service upper 4 bits */
|
||||
SDOp->Opcode = ECT_GET_OE_REQ; /* get object entry description request */
|
||||
SDOp->Reserved = 0;
|
||||
|
@ -1408,7 +1408,7 @@ int ec_TxPDO(uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout
|
|||
* @param[in] PDOassign = PDO assign object
|
||||
* @return total bitlength of PDO assign
|
||||
*/
|
||||
int ec_readPDOassign(uint16 Slave, uint16 PDOassign)
|
||||
uint32 ec_readPDOassign(uint16 Slave, uint16 PDOassign)
|
||||
{
|
||||
return ecx_readPDOassign(&ecx_context, Slave, PDOassign);
|
||||
}
|
||||
|
@ -1420,7 +1420,7 @@ int ec_readPDOassign(uint16 Slave, uint16 PDOassign)
|
|||
* @return total bitlength of PDO assign
|
||||
* @see ecx_readPDOmap
|
||||
*/
|
||||
int ec_readPDOassignCA(uint16 Slave, uint16 PDOassign, int Thread_n)
|
||||
uint32 ec_readPDOassignCA(uint16 Slave, uint16 PDOassign, int Thread_n)
|
||||
{
|
||||
return ecx_readPDOassignCA(&ecx_context, Slave, Thread_n, PDOassign);
|
||||
}
|
||||
|
@ -1438,7 +1438,7 @@ int ec_readPDOassignCA(uint16 Slave, uint16 PDOassign, int Thread_n)
|
|||
* @param[out] Isize = Size in bits of input mapping (txPDO) found
|
||||
* @return >0 if mapping succesful.
|
||||
*/
|
||||
int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize)
|
||||
int ec_readPDOmap(uint16 Slave, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
return ecx_readPDOmap(&ecx_context, Slave, Osize, Isize);
|
||||
}
|
||||
|
@ -1456,7 +1456,7 @@ int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize)
|
|||
* @return >0 if mapping succesful.
|
||||
* @see ecx_readPDOmap ec_readPDOmapCA
|
||||
*/
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, int *Osize, int *Isize)
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
return ecx_readPDOmapCA(&ecx_context, Slave, Thread_n, Osize, Isize);
|
||||
}
|
||||
|
|
|
@ -66,8 +66,8 @@ int ec_SDOwrite(uint16 Slave, uint16 Index, uint8 SubIndex,
|
|||
boolean CA, int psize, void *p, int Timeout);
|
||||
int ec_RxPDO(uint16 Slave, uint16 RxPDOnumber , int psize, void *p);
|
||||
int ec_TxPDO(uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout);
|
||||
int ec_readPDOmap(uint16 Slave, int *Osize, int *Isize);
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, int *Osize, int *Isize);
|
||||
int ec_readPDOmap(uint16 Slave, uint32 *Osize, uint32 *Isize);
|
||||
int ec_readPDOmapCA(uint16 Slave, int Thread_n, uint32 *Osize, uint32 *Isize);
|
||||
int ec_readODlist(uint16 Slave, ec_ODlistt *pODlist);
|
||||
int ec_readODdescription(uint16 Item, ec_ODlistt *pODlist);
|
||||
int ec_readOEsingle(uint16 Item, uint8 SubI, ec_ODlistt *pODlist, ec_OElistt *pOElist);
|
||||
|
@ -81,8 +81,8 @@ int ecx_SDOwrite(ecx_contextt *context, uint16 Slave, uint16 Index, uint8 SubInd
|
|||
boolean CA, int psize, void *p, int Timeout);
|
||||
int ecx_RxPDO(ecx_contextt *context, uint16 Slave, uint16 RxPDOnumber , int psize, void *p);
|
||||
int ecx_TxPDO(ecx_contextt *context, uint16 slave, uint16 TxPDOnumber , int *psize, void *p, int timeout);
|
||||
int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, int *Osize, int *Isize);
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, int *Osize, int *Isize);
|
||||
int ecx_readPDOmap(ecx_contextt *context, uint16 Slave, uint32 *Osize, uint32 *Isize);
|
||||
int ecx_readPDOmapCA(ecx_contextt *context, uint16 Slave, int Thread_n, uint32 *Osize, uint32 *Isize);
|
||||
int ecx_readODlist(ecx_contextt *context, uint16 Slave, ec_ODlistt *pODlist);
|
||||
int ecx_readODdescription(ecx_contextt *context, uint16 Item, ec_ODlistt *pODlist);
|
||||
int ecx_readOEsingle(ecx_contextt *context, uint16 Item, uint8 SubI, ec_ODlistt *pODlist, ec_OElistt *pOElist);
|
||||
|
|
|
@ -22,14 +22,6 @@
|
|||
#include "ethercatsoe.h"
|
||||
#include "ethercatconfig.h"
|
||||
|
||||
// define if debug printf is needed
|
||||
//#define EC_DEBUG
|
||||
|
||||
#ifdef EC_DEBUG
|
||||
#define EC_PRINT printf
|
||||
#else
|
||||
#define EC_PRINT(...) do {} while (0)
|
||||
#endif
|
||||
|
||||
typedef struct
|
||||
{
|
||||
|
@ -40,7 +32,9 @@ typedef struct
|
|||
} ecx_mapt_t;
|
||||
|
||||
ecx_mapt_t ecx_mapt[EC_MAX_MAPT];
|
||||
#if EC_MAX_MAPT > 1
|
||||
OSAL_THREAD_HANDLE ecx_threadh[EC_MAX_MAPT];
|
||||
#endif
|
||||
|
||||
#ifdef EC_VER1
|
||||
/** Slave configuration structure */
|
||||
|
@ -117,7 +111,8 @@ void ecx_init_context(ecx_contextt *context)
|
|||
ecx_siigetbyte(context, 0, EC_MAXEEPBUF);
|
||||
for(lp = 0; lp < context->maxgroup; lp++)
|
||||
{
|
||||
context->grouplist[lp].logstartaddr = lp << 16; /* default start address per group entry */
|
||||
/* default start address per group entry */
|
||||
context->grouplist[lp].logstartaddr = lp << EC_LOGGROUPOFFSET;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -147,7 +142,7 @@ int ecx_detect_slaves(ecx_contextt *context)
|
|||
{
|
||||
EC_PRINT("Error: too many slaves on network: num_slaves=%d, EC_MAXSLAVE=%d\n",
|
||||
wkc, EC_MAXSLAVE);
|
||||
return -2;
|
||||
return EC_SLAVECOUNTEXCEEDED;
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
|
@ -166,8 +161,8 @@ static void ecx_set_slaves_to_default(ecx_contextt *context)
|
|||
ecx_BWR(context->port, 0x0000, ECT_REG_RXERR , 8 , &zbuf, EC_TIMEOUTRET3); /* reset CRC counters */
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_FMMU0 , 16 * 3 , &zbuf, EC_TIMEOUTRET3); /* reset FMMU's */
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_SM0 , 8 * 4 , &zbuf, EC_TIMEOUTRET3); /* reset SyncM */
|
||||
b = 0x00;
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_DCSYNCACT , sizeof(b) , &b, EC_TIMEOUTRET3); /* reset activation register */
|
||||
b = 0x00;
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_DCSYNCACT , sizeof(b) , &b, EC_TIMEOUTRET3); /* reset activation register */
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_DCSYSTIME , 4 , &zbuf, EC_TIMEOUTRET3); /* reset system time+ofs */
|
||||
w = htoes(0x1000);
|
||||
ecx_BWR(context->port, 0x0000, ECT_REG_DCSPEEDCNT , sizeof(w) , &w, EC_TIMEOUTRET3); /* DC speedstart */
|
||||
|
@ -251,6 +246,8 @@ static int ecx_config_from_table(ecx_contextt *context, uint16 slave)
|
|||
#else
|
||||
static int ecx_config_from_table(ecx_contextt *context, uint16 slave)
|
||||
{
|
||||
(void)context;
|
||||
(void)slave;
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
@ -317,6 +314,7 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
uint8 SMc;
|
||||
uint32 eedat;
|
||||
int wkc, cindex, nSM;
|
||||
uint16 val16;
|
||||
|
||||
EC_PRINT("ec_config_init %d\n",usetable);
|
||||
ecx_init_context(context);
|
||||
|
@ -327,9 +325,9 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
for (slave = 1; slave <= *(context->slavecount); slave++)
|
||||
{
|
||||
ADPh = (uint16)(1 - slave);
|
||||
context->slavelist[slave].Itype =
|
||||
etohs(ecx_APRDw(context->port, ADPh, ECT_REG_PDICTL, EC_TIMEOUTRET3)); /* read interface type of slave */
|
||||
/* a node offset is used to improve readibility of network frames */
|
||||
val16 = ecx_APRDw(context->port, ADPh, ECT_REG_PDICTL, EC_TIMEOUTRET3); /* read interface type of slave */
|
||||
context->slavelist[slave].Itype = etohs(val16);
|
||||
/* a node offset is used to improve readability of network frames */
|
||||
/* this has no impact on the number of addressable slaves (auto wrap around) */
|
||||
ecx_APWRw(context->port, ADPh, ECT_REG_STADR, htoes(slave + EC_NODEOFFSET) , EC_TIMEOUTRET3); /* set node address of slave */
|
||||
if (slave == 1)
|
||||
|
@ -341,7 +339,8 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
b = 0; /* pass all frames for following slaves */
|
||||
}
|
||||
ecx_APWRw(context->port, ADPh, ECT_REG_DLCTL, htoes(b), EC_TIMEOUTRET3); /* set non ecat frame behaviour */
|
||||
configadr = etohs(ecx_APRDw(context->port, ADPh, ECT_REG_STADR, EC_TIMEOUTRET3));
|
||||
configadr = ecx_APRDw(context->port, ADPh, ECT_REG_STADR, EC_TIMEOUTRET3);
|
||||
configadr = etohs(configadr);
|
||||
context->slavelist[slave].configadr = configadr;
|
||||
ecx_FPRD(context->port, configadr, ECT_REG_ALIAS, sizeof(aliasadr), &aliasadr, EC_TIMEOUTRET3);
|
||||
context->slavelist[slave].aliasadr = etohs(aliasadr);
|
||||
|
@ -355,27 +354,27 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
}
|
||||
for (slave = 1; slave <= *(context->slavecount); slave++)
|
||||
{
|
||||
context->slavelist[slave].eep_man =
|
||||
etohl(ecx_readeeprom2(context, slave, EC_TIMEOUTEEP)); /* Manuf */
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP); /* Manuf */
|
||||
context->slavelist[slave].eep_man = etohl(eedat);
|
||||
ecx_readeeprom1(context, slave, ECT_SII_ID); /* ID */
|
||||
}
|
||||
for (slave = 1; slave <= *(context->slavecount); slave++)
|
||||
{
|
||||
context->slavelist[slave].eep_id =
|
||||
etohl(ecx_readeeprom2(context, slave, EC_TIMEOUTEEP)); /* ID */
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP); /* ID */
|
||||
context->slavelist[slave].eep_id = etohl(eedat);
|
||||
ecx_readeeprom1(context, slave, ECT_SII_REV); /* revision */
|
||||
}
|
||||
for (slave = 1; slave <= *(context->slavecount); slave++)
|
||||
{
|
||||
context->slavelist[slave].eep_rev =
|
||||
etohl(ecx_readeeprom2(context, slave, EC_TIMEOUTEEP)); /* revision */
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP); /* revision */
|
||||
context->slavelist[slave].eep_rev = etohl(eedat);
|
||||
ecx_readeeprom1(context, slave, ECT_SII_RXMBXADR); /* write mailbox address + mailboxsize */
|
||||
}
|
||||
for (slave = 1; slave <= *(context->slavecount); slave++)
|
||||
{
|
||||
eedat = etohl(ecx_readeeprom2(context, slave, EC_TIMEOUTEEP)); /* write mailbox address and mailboxsize */
|
||||
context->slavelist[slave].mbx_wo = (uint16)LO_WORD(eedat);
|
||||
context->slavelist[slave].mbx_l = (uint16)HI_WORD(eedat);
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP); /* write mailbox address and mailboxsize */
|
||||
context->slavelist[slave].mbx_wo = (uint16)LO_WORD(etohl(eedat));
|
||||
context->slavelist[slave].mbx_l = (uint16)HI_WORD(etohl(eedat));
|
||||
if (context->slavelist[slave].mbx_l > 0)
|
||||
{
|
||||
ecx_readeeprom1(context, slave, ECT_SII_TXMBXADR); /* read mailbox offset */
|
||||
|
@ -385,9 +384,9 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
{
|
||||
if (context->slavelist[slave].mbx_l > 0)
|
||||
{
|
||||
eedat = etohl(ecx_readeeprom2(context, slave, EC_TIMEOUTEEP)); /* read mailbox offset */
|
||||
context->slavelist[slave].mbx_ro = (uint16)LO_WORD(eedat); /* read mailbox offset */
|
||||
context->slavelist[slave].mbx_rl = (uint16)HI_WORD(eedat); /*read mailbox length */
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP); /* read mailbox offset */
|
||||
context->slavelist[slave].mbx_ro = (uint16)LO_WORD(etohl(eedat)); /* read mailbox offset */
|
||||
context->slavelist[slave].mbx_rl = (uint16)HI_WORD(etohl(eedat)); /*read mailbox length */
|
||||
if (context->slavelist[slave].mbx_rl == 0)
|
||||
{
|
||||
context->slavelist[slave].mbx_rl = context->slavelist[slave].mbx_l;
|
||||
|
@ -395,7 +394,8 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
ecx_readeeprom1(context, slave, ECT_SII_MBXPROTO);
|
||||
}
|
||||
configadr = context->slavelist[slave].configadr;
|
||||
if ((etohs(ecx_FPRDw(context->port, configadr, ECT_REG_ESCSUP, EC_TIMEOUTRET3)) & 0x04) > 0) /* Support DC? */
|
||||
val16 = ecx_FPRDw(context->port, configadr, ECT_REG_ESCSUP, EC_TIMEOUTRET3);
|
||||
if ((etohs(val16) & 0x04) > 0) /* Support DC? */
|
||||
{
|
||||
context->slavelist[slave].hasdc = TRUE;
|
||||
}
|
||||
|
@ -403,7 +403,8 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
{
|
||||
context->slavelist[slave].hasdc = FALSE;
|
||||
}
|
||||
topology = etohs(ecx_FPRDw(context->port, configadr, ECT_REG_DLSTAT, EC_TIMEOUTRET3)); /* extract topology from DL status */
|
||||
topology = ecx_FPRDw(context->port, configadr, ECT_REG_DLSTAT, EC_TIMEOUTRET3); /* extract topology from DL status */
|
||||
topology = etohs(topology);
|
||||
h = 0;
|
||||
b = 0;
|
||||
if ((topology & 0x0300) == 0x0200) /* port0 open and communication established */
|
||||
|
@ -427,8 +428,8 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
b |= 0x08;
|
||||
}
|
||||
/* ptype = Physical type*/
|
||||
context->slavelist[slave].ptype =
|
||||
LO_BYTE(etohs(ecx_FPRDw(context->port, configadr, ECT_REG_PORTDES, EC_TIMEOUTRET3)));
|
||||
val16 = ecx_FPRDw(context->port, configadr, ECT_REG_PORTDES, EC_TIMEOUTRET3);
|
||||
context->slavelist[slave].ptype = LO_BYTE(etohs(val16));
|
||||
context->slavelist[slave].topology = h;
|
||||
context->slavelist[slave].activeports = b;
|
||||
/* 0=no links, not possible */
|
||||
|
@ -482,8 +483,8 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
context->slavelist[slave].SM[1].StartAddr = htoes(context->slavelist[slave].mbx_ro);
|
||||
context->slavelist[slave].SM[1].SMlength = htoes(context->slavelist[slave].mbx_rl);
|
||||
context->slavelist[slave].SM[1].SMflags = htoel(EC_DEFAULTMBXSM1);
|
||||
context->slavelist[slave].mbx_proto =
|
||||
ecx_readeeprom2(context, slave, EC_TIMEOUTEEP);
|
||||
eedat = ecx_readeeprom2(context, slave, EC_TIMEOUTEEP);
|
||||
context->slavelist[slave].mbx_proto = (uint16)etohl(eedat);
|
||||
}
|
||||
cindex = 0;
|
||||
/* use configuration table ? */
|
||||
|
@ -588,8 +589,16 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
}
|
||||
/* some slaves need eeprom available to PDI in init->preop transition */
|
||||
ecx_eeprom2pdi(context, slave);
|
||||
/* request pre_op for slave */
|
||||
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_PRE_OP | EC_STATE_ACK) , EC_TIMEOUTRET3); /* set preop status */
|
||||
/* User may override automatic state change */
|
||||
if (context->manualstatechange == 0)
|
||||
{
|
||||
/* request pre_op for slave */
|
||||
ecx_FPWRw(context->port,
|
||||
configadr,
|
||||
ECT_REG_ALCTL,
|
||||
htoes(EC_STATE_PRE_OP | EC_STATE_ACK),
|
||||
EC_TIMEOUTRET3); /* set preop status */
|
||||
}
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
|
@ -598,7 +607,7 @@ int ecx_config_init(ecx_contextt *context, uint8 usetable)
|
|||
/* If slave has SII mapping and same slave ID done before, use previous mapping.
|
||||
* This is safe because SII mapping is constant for same slave ID.
|
||||
*/
|
||||
static int ecx_lookup_mapping(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
||||
static int ecx_lookup_mapping(ecx_contextt *context, uint16 slave, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
int i, nSM;
|
||||
if ((slave > 1) && (*(context->slavecount) > 0))
|
||||
|
@ -620,8 +629,8 @@ static int ecx_lookup_mapping(ecx_contextt *context, uint16 slave, int *Osize, i
|
|||
}
|
||||
*Osize = context->slavelist[i].Obits;
|
||||
*Isize = context->slavelist[i].Ibits;
|
||||
context->slavelist[slave].Obits = *Osize;
|
||||
context->slavelist[slave].Ibits = *Isize;
|
||||
context->slavelist[slave].Obits = (uint16)*Osize;
|
||||
context->slavelist[slave].Ibits = (uint16)*Isize;
|
||||
EC_PRINT("Copy mapping slave %d from %d.\n", slave, i);
|
||||
return 1;
|
||||
}
|
||||
|
@ -631,7 +640,7 @@ static int ecx_lookup_mapping(ecx_contextt *context, uint16 slave, int *Osize, i
|
|||
|
||||
static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
|
||||
{
|
||||
int Isize, Osize;
|
||||
uint32 Isize, Osize;
|
||||
int rval;
|
||||
|
||||
ecx_statecheck(context, slave, EC_STATE_PRE_OP, EC_TIMEOUTSTATE); /* check state change pre-op */
|
||||
|
@ -644,6 +653,10 @@ static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
|
|||
{
|
||||
context->slavelist[slave].PO2SOconfig(slave);
|
||||
}
|
||||
if (context->slavelist[slave].PO2SOconfigx) /* only if registered */
|
||||
{
|
||||
context->slavelist[slave].PO2SOconfigx(context, slave);
|
||||
}
|
||||
/* if slave not found in configlist find IO mapping in slave self */
|
||||
if (!context->slavelist[slave].configindex)
|
||||
{
|
||||
|
@ -662,18 +675,18 @@ static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
|
|||
/* read PDO mapping via CoE */
|
||||
rval = ecx_readPDOmap(context, slave, &Osize, &Isize);
|
||||
}
|
||||
EC_PRINT(" CoE Osize:%d Isize:%d\n", Osize, Isize);
|
||||
EC_PRINT(" CoE Osize:%u Isize:%u\n", Osize, Isize);
|
||||
}
|
||||
if ((!Isize && !Osize) && (context->slavelist[slave].mbx_proto & ECT_MBXPROT_SOE)) /* has SoE */
|
||||
{
|
||||
/* read AT / MDT mapping via SoE */
|
||||
rval = ecx_readIDNmap(context, slave, &Osize, &Isize);
|
||||
context->slavelist[slave].SM[2].SMlength = htoes((Osize + 7) / 8);
|
||||
context->slavelist[slave].SM[3].SMlength = htoes((Isize + 7) / 8);
|
||||
EC_PRINT(" SoE Osize:%d Isize:%d\n", Osize, Isize);
|
||||
context->slavelist[slave].SM[2].SMlength = htoes((uint16)((Osize + 7) / 8));
|
||||
context->slavelist[slave].SM[3].SMlength = htoes((uint16)((Isize + 7) / 8));
|
||||
EC_PRINT(" SoE Osize:%u Isize:%u\n", Osize, Isize);
|
||||
}
|
||||
context->slavelist[slave].Obits = Osize;
|
||||
context->slavelist[slave].Ibits = Isize;
|
||||
context->slavelist[slave].Obits = (uint16)Osize;
|
||||
context->slavelist[slave].Ibits = (uint16)Isize;
|
||||
}
|
||||
|
||||
return 1;
|
||||
|
@ -681,7 +694,7 @@ static int ecx_map_coe_soe(ecx_contextt *context, uint16 slave, int thread_n)
|
|||
|
||||
static int ecx_map_sii(ecx_contextt *context, uint16 slave)
|
||||
{
|
||||
int Isize, Osize;
|
||||
uint32 Isize, Osize;
|
||||
int nSM;
|
||||
ec_eepromPDOt eepPDO;
|
||||
|
||||
|
@ -695,8 +708,8 @@ static int ecx_map_sii(ecx_contextt *context, uint16 slave)
|
|||
if (!Isize && !Osize) /* find PDO mapping by SII */
|
||||
{
|
||||
memset(&eepPDO, 0, sizeof(eepPDO));
|
||||
Isize = (int)ecx_siiPDO(context, slave, &eepPDO, 0);
|
||||
EC_PRINT(" SII Isize:%d\n", Isize);
|
||||
Isize = ecx_siiPDO(context, slave, &eepPDO, 0);
|
||||
EC_PRINT(" SII Isize:%u\n", Isize);
|
||||
for( nSM=0 ; nSM < EC_MAXSM ; nSM++ )
|
||||
{
|
||||
if (eepPDO.SMbitsize[nSM] > 0)
|
||||
|
@ -706,8 +719,8 @@ static int ecx_map_sii(ecx_contextt *context, uint16 slave)
|
|||
EC_PRINT(" SM%d length %d\n", nSM, eepPDO.SMbitsize[nSM]);
|
||||
}
|
||||
}
|
||||
Osize = (int)ecx_siiPDO(context, slave, &eepPDO, 1);
|
||||
EC_PRINT(" SII Osize:%d\n", Osize);
|
||||
Osize = ecx_siiPDO(context, slave, &eepPDO, 1);
|
||||
EC_PRINT(" SII Osize:%u\n", Osize);
|
||||
for( nSM=0 ; nSM < EC_MAXSM ; nSM++ )
|
||||
{
|
||||
if (eepPDO.SMbitsize[nSM] > 0)
|
||||
|
@ -718,8 +731,8 @@ static int ecx_map_sii(ecx_contextt *context, uint16 slave)
|
|||
}
|
||||
}
|
||||
}
|
||||
context->slavelist[slave].Obits = Osize;
|
||||
context->slavelist[slave].Ibits = Isize;
|
||||
context->slavelist[slave].Obits = (uint16)Osize;
|
||||
context->slavelist[slave].Ibits = (uint16)Isize;
|
||||
EC_PRINT(" ISIZE:%d %d OSIZE:%d\n",
|
||||
context->slavelist[slave].Ibits, Isize,context->slavelist[slave].Obits);
|
||||
|
||||
|
@ -740,8 +753,8 @@ static int ecx_map_sm(ecx_contextt *context, uint16 slave)
|
|||
sizeof(ec_smt), &(context->slavelist[slave].SM[0]), EC_TIMEOUTRET3);
|
||||
EC_PRINT(" SM0 Type:%d StartAddr:%4.4x Flags:%8.8x\n",
|
||||
context->slavelist[slave].SMtype[0],
|
||||
context->slavelist[slave].SM[0].StartAddr,
|
||||
context->slavelist[slave].SM[0].SMflags);
|
||||
etohs(context->slavelist[slave].SM[0].StartAddr),
|
||||
etohl(context->slavelist[slave].SM[0].SMflags));
|
||||
}
|
||||
if (!context->slavelist[slave].mbx_l && context->slavelist[slave].SM[1].StartAddr)
|
||||
{
|
||||
|
@ -749,8 +762,8 @@ static int ecx_map_sm(ecx_contextt *context, uint16 slave)
|
|||
sizeof(ec_smt), &context->slavelist[slave].SM[1], EC_TIMEOUTRET3);
|
||||
EC_PRINT(" SM1 Type:%d StartAddr:%4.4x Flags:%8.8x\n",
|
||||
context->slavelist[slave].SMtype[1],
|
||||
context->slavelist[slave].SM[1].StartAddr,
|
||||
context->slavelist[slave].SM[1].SMflags);
|
||||
etohs(context->slavelist[slave].SM[1].StartAddr),
|
||||
etohl(context->slavelist[slave].SM[1].SMflags));
|
||||
}
|
||||
/* program SM2 to SMx */
|
||||
for( nSM = 2 ; nSM < EC_MAXSM ; nSM++ )
|
||||
|
@ -763,12 +776,18 @@ static int ecx_map_sm(ecx_contextt *context, uint16 slave)
|
|||
context->slavelist[slave].SM[nSM].SMflags =
|
||||
htoel( etohl(context->slavelist[slave].SM[nSM].SMflags) & EC_SMENABLEMASK);
|
||||
}
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_SM0 + (nSM * sizeof(ec_smt)),
|
||||
/* if SM length is non zero always set enable flag */
|
||||
else
|
||||
{
|
||||
context->slavelist[slave].SM[nSM].SMflags =
|
||||
htoel( etohl(context->slavelist[slave].SM[nSM].SMflags) | ~EC_SMENABLEMASK);
|
||||
}
|
||||
ecx_FPWR(context->port, configadr, (uint16)(ECT_REG_SM0 + (nSM * sizeof(ec_smt))),
|
||||
sizeof(ec_smt), &context->slavelist[slave].SM[nSM], EC_TIMEOUTRET3);
|
||||
EC_PRINT(" SM%d Type:%d StartAddr:%4.4x Flags:%8.8x\n", nSM,
|
||||
context->slavelist[slave].SMtype[nSM],
|
||||
context->slavelist[slave].SM[nSM].StartAddr,
|
||||
context->slavelist[slave].SM[nSM].SMflags);
|
||||
etohs(context->slavelist[slave].SM[nSM].StartAddr),
|
||||
etohl(context->slavelist[slave].SM[nSM].SMflags));
|
||||
}
|
||||
}
|
||||
if (context->slavelist[slave].Ibits > 7)
|
||||
|
@ -783,6 +802,7 @@ static int ecx_map_sm(ecx_contextt *context, uint16 slave)
|
|||
return 1;
|
||||
}
|
||||
|
||||
#if EC_MAX_MAPT > 1
|
||||
OSAL_THREAD_FUNC ecx_mapper_thread(void *param)
|
||||
{
|
||||
ecx_mapt_t *maptp;
|
||||
|
@ -808,6 +828,7 @@ static int ecx_find_mapt(void)
|
|||
return -1;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static int ecx_get_threadcount(void)
|
||||
{
|
||||
|
@ -834,13 +855,7 @@ static void ecx_config_find_mappings(ecx_contextt *context, uint8 group)
|
|||
{
|
||||
if (!group || (group == context->slavelist[slave].group))
|
||||
{
|
||||
if (EC_MAX_MAPT <= 1)
|
||||
{
|
||||
/* serialised version */
|
||||
ecx_map_coe_soe(context, slave, 0);
|
||||
}
|
||||
else
|
||||
{
|
||||
#if EC_MAX_MAPT > 1
|
||||
/* multi-threaded version */
|
||||
while ((thrn = ecx_find_mapt()) < 0)
|
||||
{
|
||||
|
@ -852,7 +867,10 @@ static void ecx_config_find_mappings(ecx_contextt *context, uint8 group)
|
|||
ecx_mapt[thrn].running = 1;
|
||||
osal_thread_create(&(ecx_threadh[thrn]), 128000,
|
||||
&ecx_mapper_thread, &(ecx_mapt[thrn]));
|
||||
}
|
||||
#else
|
||||
/* serialised version */
|
||||
ecx_map_coe_soe(context, slave, 0);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
/* wait for all threads to finish */
|
||||
|
@ -879,9 +897,10 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
uint8 group, int16 slave, uint32 * LogAddr, uint8 * BitPos)
|
||||
{
|
||||
int BitCount = 0;
|
||||
int ByteCount = 0;
|
||||
int FMMUsize = 0;
|
||||
int FMMUdone = 0;
|
||||
int AddToInputsWKC = 0;
|
||||
uint16 ByteCount = 0;
|
||||
uint16 FMMUsize = 0;
|
||||
uint8 SMc = 0;
|
||||
uint16 EndAddr;
|
||||
uint16 SMlength;
|
||||
|
@ -921,7 +940,7 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
{
|
||||
SMc++;
|
||||
}
|
||||
/* if addresses from more SM connect use one FMMU otherwise break up in mutiple FMMU */
|
||||
/* if addresses from more SM connect use one FMMU otherwise break up in multiple FMMU */
|
||||
if (etohs(context->slavelist[slave].SM[SMc].StartAddr) > EndAddr)
|
||||
{
|
||||
break;
|
||||
|
@ -944,7 +963,7 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
*LogAddr += 1;
|
||||
*BitPos -= 8;
|
||||
}
|
||||
FMMUsize = *LogAddr - etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) + 1;
|
||||
FMMUsize = (uint16)(*LogAddr - etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) + 1);
|
||||
context->slavelist[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
|
||||
context->slavelist[slave].FMMU[FMMUc].LogEndbit = *BitPos;
|
||||
*BitPos += 1;
|
||||
|
@ -968,7 +987,7 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
FMMUsize = ByteCount;
|
||||
if ((FMMUsize + FMMUdone)> (int)context->slavelist[slave].Ibytes)
|
||||
{
|
||||
FMMUsize = context->slavelist[slave].Ibytes - FMMUdone;
|
||||
FMMUsize = (uint16)(context->slavelist[slave].Ibytes - FMMUdone);
|
||||
}
|
||||
*LogAddr += FMMUsize;
|
||||
context->slavelist[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
|
||||
|
@ -984,13 +1003,25 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
/* program FMMU for input */
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc),
|
||||
sizeof(ec_fmmut), &(context->slavelist[slave].FMMU[FMMUc]), EC_TIMEOUTRET3);
|
||||
/* add one for an input FMMU */
|
||||
context->grouplist[group].inputsWKC++;
|
||||
/* Set flag to add one for an input FMMU,
|
||||
a single ESC can only contribute once */
|
||||
AddToInputsWKC = 1;
|
||||
}
|
||||
if (!context->slavelist[slave].inputs)
|
||||
{
|
||||
context->slavelist[slave].inputs =
|
||||
(uint8 *)(pIOmap)+etohl(context->slavelist[slave].FMMU[FMMUc].LogStart);
|
||||
if (group)
|
||||
{
|
||||
context->slavelist[slave].inputs =
|
||||
(uint8 *)(pIOmap) +
|
||||
etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) -
|
||||
context->grouplist[group].logstartaddr;
|
||||
}
|
||||
else
|
||||
{
|
||||
context->slavelist[slave].inputs =
|
||||
(uint8 *)(pIOmap) +
|
||||
etohl(context->slavelist[slave].FMMU[FMMUc].LogStart);
|
||||
}
|
||||
context->slavelist[slave].Istartbit =
|
||||
context->slavelist[slave].FMMU[FMMUc].LogStartbit;
|
||||
EC_PRINT(" Inputs %p startbit %d\n",
|
||||
|
@ -1000,15 +1031,20 @@ static void ecx_config_create_input_mappings(ecx_contextt *context, void *pIOmap
|
|||
FMMUc++;
|
||||
}
|
||||
context->slavelist[slave].FMMUunused = FMMUc;
|
||||
|
||||
/* Add one WKC for an input if flag is true */
|
||||
if (AddToInputsWKC)
|
||||
context->grouplist[group].inputsWKC++;
|
||||
}
|
||||
|
||||
static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOmap,
|
||||
uint8 group, int16 slave, uint32 * LogAddr, uint8 * BitPos)
|
||||
{
|
||||
int BitCount = 0;
|
||||
int ByteCount = 0;
|
||||
int FMMUsize = 0;
|
||||
int FMMUdone = 0;
|
||||
int AddToOutputsWKC = 0;
|
||||
uint16 ByteCount = 0;
|
||||
uint16 FMMUsize = 0;
|
||||
uint8 SMc = 0;
|
||||
uint16 EndAddr;
|
||||
uint16 SMlength;
|
||||
|
@ -1042,7 +1078,7 @@ static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOma
|
|||
{
|
||||
SMc++;
|
||||
}
|
||||
/* if addresses from more SM connect use one FMMU otherwise break up in mutiple FMMU */
|
||||
/* if addresses from more SM connect use one FMMU otherwise break up in multiple FMMU */
|
||||
if (etohs(context->slavelist[slave].SM[SMc].StartAddr) > EndAddr)
|
||||
{
|
||||
break;
|
||||
|
@ -1065,7 +1101,7 @@ static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOma
|
|||
*LogAddr += 1;
|
||||
*BitPos -= 8;
|
||||
}
|
||||
FMMUsize = *LogAddr - etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) + 1;
|
||||
FMMUsize = (uint16)(*LogAddr - etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) + 1);
|
||||
context->slavelist[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
|
||||
context->slavelist[slave].FMMU[FMMUc].LogEndbit = *BitPos;
|
||||
*BitPos += 1;
|
||||
|
@ -1089,7 +1125,7 @@ static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOma
|
|||
FMMUsize = ByteCount;
|
||||
if ((FMMUsize + FMMUdone)> (int)context->slavelist[slave].Obytes)
|
||||
{
|
||||
FMMUsize = context->slavelist[slave].Obytes - FMMUdone;
|
||||
FMMUsize = (uint16)(context->slavelist[slave].Obytes - FMMUdone);
|
||||
}
|
||||
*LogAddr += FMMUsize;
|
||||
context->slavelist[slave].FMMU[FMMUc].LogLength = htoes(FMMUsize);
|
||||
|
@ -1097,17 +1133,33 @@ static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOma
|
|||
*BitPos = 0;
|
||||
}
|
||||
FMMUdone += FMMUsize;
|
||||
context->slavelist[slave].FMMU[FMMUc].PhysStartBit = 0;
|
||||
context->slavelist[slave].FMMU[FMMUc].FMMUtype = 2;
|
||||
context->slavelist[slave].FMMU[FMMUc].FMMUactive = 1;
|
||||
/* program FMMU for output */
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc),
|
||||
sizeof(ec_fmmut), &(context->slavelist[slave].FMMU[FMMUc]), EC_TIMEOUTRET3);
|
||||
context->grouplist[group].outputsWKC++;
|
||||
if (context->slavelist[slave].FMMU[FMMUc].LogLength)
|
||||
{
|
||||
context->slavelist[slave].FMMU[FMMUc].PhysStartBit = 0;
|
||||
context->slavelist[slave].FMMU[FMMUc].FMMUtype = 2;
|
||||
context->slavelist[slave].FMMU[FMMUc].FMMUactive = 1;
|
||||
/* program FMMU for output */
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc),
|
||||
sizeof(ec_fmmut), &(context->slavelist[slave].FMMU[FMMUc]), EC_TIMEOUTRET3);
|
||||
/* Set flag to add one for an output FMMU,
|
||||
a single ESC can only contribute once */
|
||||
AddToOutputsWKC = 1;
|
||||
}
|
||||
if (!context->slavelist[slave].outputs)
|
||||
{
|
||||
context->slavelist[slave].outputs =
|
||||
(uint8 *)(pIOmap)+etohl(context->slavelist[slave].FMMU[FMMUc].LogStart);
|
||||
if (group)
|
||||
{
|
||||
context->slavelist[slave].outputs =
|
||||
(uint8 *)(pIOmap) +
|
||||
etohl(context->slavelist[slave].FMMU[FMMUc].LogStart) -
|
||||
context->grouplist[group].logstartaddr;
|
||||
}
|
||||
else
|
||||
{
|
||||
context->slavelist[slave].outputs =
|
||||
(uint8 *)(pIOmap) +
|
||||
etohl(context->slavelist[slave].FMMU[FMMUc].LogStart);
|
||||
}
|
||||
context->slavelist[slave].Ostartbit =
|
||||
context->slavelist[slave].FMMU[FMMUc].LogStartbit;
|
||||
EC_PRINT(" slave %d Outputs %p startbit %d\n",
|
||||
|
@ -1118,6 +1170,9 @@ static void ecx_config_create_output_mappings(ecx_contextt *context, void *pIOma
|
|||
FMMUc++;
|
||||
}
|
||||
context->slavelist[slave].FMMUunused = FMMUc;
|
||||
/* Add one WKC for an output if flag is true */
|
||||
if (AddToOutputsWKC)
|
||||
context->grouplist[group].outputsWKC++;
|
||||
}
|
||||
|
||||
/** Map all PDOs in one group of slaves to IOmap with Outputs/Inputs
|
||||
|
@ -1201,14 +1256,15 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
}
|
||||
}
|
||||
context->grouplist[group].outputs = pIOmap;
|
||||
context->grouplist[group].Obytes = LogAddr;
|
||||
context->grouplist[group].Obytes = LogAddr - context->grouplist[group].logstartaddr;
|
||||
context->grouplist[group].nsegments = currentsegment + 1;
|
||||
context->grouplist[group].Isegment = currentsegment;
|
||||
context->grouplist[group].Ioffset = segmentsize;
|
||||
context->grouplist[group].Ioffset = (uint16)segmentsize;
|
||||
if (!group)
|
||||
{
|
||||
context->slavelist[0].outputs = pIOmap;
|
||||
context->slavelist[0].Obytes = LogAddr; /* store output bytes in master record */
|
||||
context->slavelist[0].Obytes = LogAddr -
|
||||
context->grouplist[group].logstartaddr; /* store output bytes in master record */
|
||||
}
|
||||
|
||||
/* do input mapping of slave and program FMMUs */
|
||||
|
@ -1240,8 +1296,16 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
}
|
||||
|
||||
ecx_eeprom2pdi(context, slave); /* set Eeprom control to PDI */
|
||||
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP) , EC_TIMEOUTRET3); /* set safeop status */
|
||||
|
||||
/* User may override automatic state change */
|
||||
if (context->manualstatechange == 0)
|
||||
{
|
||||
/* request safe_op for slave */
|
||||
ecx_FPWRw(context->port,
|
||||
configadr,
|
||||
ECT_REG_ALCTL,
|
||||
htoes(EC_STATE_SAFE_OP),
|
||||
EC_TIMEOUTRET3); /* set safeop status */
|
||||
}
|
||||
if (context->slavelist[slave].blockLRW)
|
||||
{
|
||||
context->grouplist[group].blockLRW++;
|
||||
|
@ -1271,11 +1335,15 @@ int ecx_config_map_group(ecx_contextt *context, void *pIOmap, uint8 group)
|
|||
context->grouplist[group].IOsegment[currentsegment] = segmentsize;
|
||||
context->grouplist[group].nsegments = currentsegment + 1;
|
||||
context->grouplist[group].inputs = (uint8 *)(pIOmap) + context->grouplist[group].Obytes;
|
||||
context->grouplist[group].Ibytes = LogAddr - context->grouplist[group].Obytes;
|
||||
context->grouplist[group].Ibytes = LogAddr -
|
||||
context->grouplist[group].logstartaddr -
|
||||
context->grouplist[group].Obytes;
|
||||
if (!group)
|
||||
{
|
||||
context->slavelist[0].inputs = (uint8 *)(pIOmap) + context->slavelist[0].Obytes;
|
||||
context->slavelist[0].Ibytes = LogAddr - context->slavelist[0].Obytes; /* store input bytes in master record */
|
||||
context->slavelist[0].Ibytes = LogAddr -
|
||||
context->grouplist[group].logstartaddr -
|
||||
context->slavelist[0].Obytes; /* store input bytes in master record */
|
||||
}
|
||||
|
||||
EC_PRINT("IOmapSize %d\n", LogAddr - context->grouplist[group].logstartaddr);
|
||||
|
@ -1372,8 +1440,16 @@ int ecx_config_overlap_map_group(ecx_contextt *context, void *pIOmap, uint8 grou
|
|||
}
|
||||
|
||||
ecx_eeprom2pdi(context, slave); /* set Eeprom control to PDI */
|
||||
ecx_FPWRw(context->port, configadr, ECT_REG_ALCTL, htoes(EC_STATE_SAFE_OP), EC_TIMEOUTRET3); /* set safeop status */
|
||||
|
||||
/* User may override automatic state change */
|
||||
if (context->manualstatechange == 0)
|
||||
{
|
||||
/* request safe_op for slave */
|
||||
ecx_FPWRw(context->port,
|
||||
configadr,
|
||||
ECT_REG_ALCTL,
|
||||
htoes(EC_STATE_SAFE_OP),
|
||||
EC_TIMEOUTRET3);
|
||||
}
|
||||
if (context->slavelist[slave].blockLRW)
|
||||
{
|
||||
context->grouplist[group].blockLRW++;
|
||||
|
@ -1388,8 +1464,8 @@ int ecx_config_overlap_map_group(ecx_contextt *context, void *pIOmap, uint8 grou
|
|||
context->grouplist[group].Isegment = 0;
|
||||
context->grouplist[group].Ioffset = 0;
|
||||
|
||||
context->grouplist[group].Obytes = soLogAddr;
|
||||
context->grouplist[group].Ibytes = siLogAddr;
|
||||
context->grouplist[group].Obytes = soLogAddr - context->grouplist[group].logstartaddr;
|
||||
context->grouplist[group].Ibytes = siLogAddr - context->grouplist[group].logstartaddr;
|
||||
context->grouplist[group].outputs = pIOmap;
|
||||
context->grouplist[group].inputs = (uint8 *)pIOmap + context->grouplist[group].Obytes;
|
||||
|
||||
|
@ -1401,10 +1477,11 @@ int ecx_config_overlap_map_group(ecx_contextt *context, void *pIOmap, uint8 grou
|
|||
|
||||
if (!group)
|
||||
{
|
||||
/* store output bytes in master record */
|
||||
context->slavelist[0].outputs = pIOmap;
|
||||
context->slavelist[0].Obytes = soLogAddr; /* store output bytes in master record */
|
||||
context->slavelist[0].Obytes = soLogAddr - context->grouplist[group].logstartaddr;
|
||||
context->slavelist[0].inputs = (uint8 *)pIOmap + context->slavelist[0].Obytes;
|
||||
context->slavelist[0].Ibytes = siLogAddr;
|
||||
context->slavelist[0].Ibytes = siLogAddr - context->grouplist[group].logstartaddr;
|
||||
}
|
||||
|
||||
EC_PRINT("IOmapSize %d\n", context->grouplist[group].Obytes + context->grouplist[group].Ibytes);
|
||||
|
@ -1457,13 +1534,13 @@ int ecx_recover_slave(ecx_contextt *context, uint16 slave, int timeout)
|
|||
|
||||
/* check if slave is the same as configured before */
|
||||
if ((ecx_FPRDw(context->port, EC_TEMPNODE, ECT_REG_ALIAS, timeout) ==
|
||||
context->slavelist[slave].aliasadr) &&
|
||||
htoes(context->slavelist[slave].aliasadr)) &&
|
||||
(ecx_readeeprom(context, slave, ECT_SII_ID, EC_TIMEOUTEEP) ==
|
||||
context->slavelist[slave].eep_id) &&
|
||||
htoel(context->slavelist[slave].eep_id)) &&
|
||||
(ecx_readeeprom(context, slave, ECT_SII_MANUF, EC_TIMEOUTEEP) ==
|
||||
context->slavelist[slave].eep_man) &&
|
||||
htoel(context->slavelist[slave].eep_man)) &&
|
||||
(ecx_readeeprom(context, slave, ECT_SII_REV, EC_TIMEOUTEEP) ==
|
||||
context->slavelist[slave].eep_rev))
|
||||
htoel(context->slavelist[slave].eep_rev)))
|
||||
{
|
||||
rval = ecx_FPWRw(context->port, EC_TEMPNODE, ECT_REG_STADR, htoes(configadr) , timeout);
|
||||
context->slavelist[slave].configadr = configadr;
|
||||
|
@ -1507,7 +1584,7 @@ int ecx_reconfig_slave(ecx_contextt *context, uint16 slave, int timeout)
|
|||
{
|
||||
if (context->slavelist[slave].SM[nSM].StartAddr)
|
||||
{
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_SM0 + (nSM * sizeof(ec_smt)),
|
||||
ecx_FPWR(context->port, configadr, (uint16)(ECT_REG_SM0 + (nSM * sizeof(ec_smt))),
|
||||
sizeof(ec_smt), &context->slavelist[slave].SM[nSM], timeout);
|
||||
}
|
||||
}
|
||||
|
@ -1525,7 +1602,7 @@ int ecx_reconfig_slave(ecx_contextt *context, uint16 slave, int timeout)
|
|||
/* program configured FMMU */
|
||||
for( FMMUc = 0 ; FMMUc < context->slavelist[slave].FMMUunused ; FMMUc++ )
|
||||
{
|
||||
ecx_FPWR(context->port, configadr, ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc),
|
||||
ecx_FPWR(context->port, configadr, (uint16)(ECT_REG_FMMU0 + (sizeof(ec_fmmut) * FMMUc)),
|
||||
sizeof(ec_fmmut), &context->slavelist[slave].FMMU[FMMUc], timeout);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
/** \file
|
||||
* \brief
|
||||
* DEPRICATED Configuration list of known EtherCAT slave devices.
|
||||
* DEPRECATED Configuration list of known EtherCAT slave devices.
|
||||
*
|
||||
* If a slave is found in this list it is configured according to the parameters
|
||||
* in the list. Otherwise the configuration info is read directly from the slave
|
||||
|
|
|
@ -56,7 +56,7 @@ void ecx_dcsync0(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclTi
|
|||
|
||||
/* Calculate first trigger time, always a whole multiple of CyclTime rounded up
|
||||
plus the shifttime (can be negative)
|
||||
This insures best sychronisation between slaves, slaves with the same CyclTime
|
||||
This insures best synchronization between slaves, slaves with the same CyclTime
|
||||
will sync at the same moment (you can use CyclShift to shift the sync) */
|
||||
if (CyclTime > 0)
|
||||
{
|
||||
|
@ -119,7 +119,7 @@ void ecx_dcsync01(ecx_contextt *context, uint16 slave, boolean act, uint32 CyclT
|
|||
|
||||
/* Calculate first trigger time, always a whole multiple of TrueCyclTime rounded up
|
||||
plus the shifttime (can be negative)
|
||||
This insures best sychronisation between slaves, slaves with the same CyclTime
|
||||
This insures best synchronization between slaves, slaves with the same CyclTime
|
||||
will sync at the same moment (you can use CyclShift to shift the sync) */
|
||||
if (CyclTime0 > 0)
|
||||
{
|
||||
|
@ -281,8 +281,8 @@ boolean ecx_configdc(ecx_contextt *context)
|
|||
context->slavelist[0].hasdc = TRUE;
|
||||
context->slavelist[0].DCnext = i;
|
||||
context->slavelist[i].DCprevious = 0;
|
||||
context->grouplist[0].hasdc = TRUE;
|
||||
context->grouplist[0].DCnext = i;
|
||||
context->grouplist[context->slavelist[i].group].hasdc = TRUE;
|
||||
context->grouplist[context->slavelist[i].group].DCnext = i;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
|
|
@ -0,0 +1,633 @@
|
|||
/*
|
||||
* Licensed under the GNU General Public License version 2 with exceptions. See
|
||||
* LICENSE file in the project root for full license information
|
||||
*/
|
||||
|
||||
/** \file
|
||||
* \brief
|
||||
* Ethernet over EtherCAT (EoE) module.
|
||||
*
|
||||
* Set / Get IP functions
|
||||
* Blocking send/receive Ethernet Frame
|
||||
* Read incoming EoE fragment to Ethernet Frame
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include "osal.h"
|
||||
#include "oshw.h"
|
||||
#include "ethercat.h"
|
||||
|
||||
/** EoE utility function to convert uint32 to eoe ip bytes.
|
||||
* @param[in] ip = ip in uint32
|
||||
* @param[out] byte_ip = eoe ip 4th octet, 3ed octet, 2nd octet, 1st octet
|
||||
*/
|
||||
static void EOE_ip_uint32_to_byte(eoe_ip4_addr_t * ip, uint8_t * byte_ip)
|
||||
{
|
||||
byte_ip[3] = eoe_ip4_addr1(ip); /* 1st octet */
|
||||
byte_ip[2] = eoe_ip4_addr2(ip); /* 2nd octet */
|
||||
byte_ip[1] = eoe_ip4_addr3(ip); /* 3ed octet */
|
||||
byte_ip[0] = eoe_ip4_addr4(ip); /* 4th octet */
|
||||
}
|
||||
|
||||
/** EoE utility function to convert eoe ip bytes to uint32.
|
||||
* @param[in] byte_ip = eoe ip 4th octet, 3ed octet, 2nd octet, 1st octet
|
||||
* @param[out] ip = ip in uint32
|
||||
*/
|
||||
static void EOE_ip_byte_to_uint32(uint8_t * byte_ip, eoe_ip4_addr_t * ip)
|
||||
{
|
||||
EOE_IP4_ADDR_TO_U32(ip,
|
||||
byte_ip[3], /* 1st octet */
|
||||
byte_ip[2], /* 2nd octet */
|
||||
byte_ip[1], /* 3ed octet */
|
||||
byte_ip[0]); /* 4th octet */
|
||||
}
|
||||
|
||||
/** EoE fragment data handler hook. Should not block.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] hook = Pointer to hook function.
|
||||
* @return 1
|
||||
*/
|
||||
int ecx_EOEdefinehook(ecx_contextt *context, void *hook)
|
||||
{
|
||||
context->EOEhook = hook;
|
||||
return 1;
|
||||
}
|
||||
|
||||
/** EoE EOE set IP, blocking. Waits for response from the slave.
|
||||
*
|
||||
* @param[in] context = Context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] port = Port number on slave if applicable
|
||||
* @param[in] ipparam = IP parameter data to be sent
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response or returned result code
|
||||
*/
|
||||
int ecx_EOEsetIp(ecx_contextt *context, uint16 slave, uint8 port, eoe_param_t * ipparam, int timeout)
|
||||
{
|
||||
ec_EOEt *EOEp, *aEOEp;
|
||||
ec_mbxbuft MbxIn, MbxOut;
|
||||
uint16 frameinfo1, result;
|
||||
uint8 cnt, data_offset;
|
||||
uint8 flags = 0;
|
||||
int wkc;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aEOEp = (ec_EOEt *)&MbxIn;
|
||||
EOEp = (ec_EOEt *)&MbxOut;
|
||||
EOEp->mbxheader.address = htoes(0x0000);
|
||||
EOEp->mbxheader.priority = 0x00;
|
||||
data_offset = EOE_PARAM_OFFSET;
|
||||
|
||||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
|
||||
EOEp->mbxheader.mbxtype = ECT_MBXT_EOE + MBX_HDR_SET_CNT(cnt); /* EoE */
|
||||
|
||||
EOEp->frameinfo1 = htoes(EOE_HDR_FRAME_TYPE_SET(EOE_INIT_REQ) |
|
||||
EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_HDR_LAST_FRAGMENT);
|
||||
EOEp->frameinfo2 = 0;
|
||||
|
||||
if (ipparam->mac_set)
|
||||
{
|
||||
flags |= EOE_PARAM_MAC_INCLUDE;
|
||||
memcpy(&EOEp->data[data_offset], ipparam->mac.addr, EOE_ETHADDR_LENGTH);
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
}
|
||||
if (ipparam->ip_set)
|
||||
{
|
||||
flags |= EOE_PARAM_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&ipparam->ip, &EOEp->data[data_offset]);
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (ipparam->subnet_set)
|
||||
{
|
||||
flags |= EOE_PARAM_SUBNET_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&ipparam->subnet, &EOEp->data[data_offset]);
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (ipparam->default_gateway_set)
|
||||
{
|
||||
flags |= EOE_PARAM_DEFAULT_GATEWAY_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&ipparam->default_gateway, &EOEp->data[data_offset]);
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (ipparam->dns_ip_set)
|
||||
{
|
||||
flags |= EOE_PARAM_DNS_IP_INCLUDE;
|
||||
EOE_ip_uint32_to_byte(&ipparam->dns_ip, &EOEp->data[data_offset]);
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (ipparam->dns_name_set)
|
||||
{
|
||||
/* TwinCAT include EOE_DNS_NAME_LENGTH chars even if name is shorter */
|
||||
flags |= EOE_PARAM_DNS_NAME_INCLUDE;
|
||||
memcpy(&EOEp->data[data_offset], (void *)ipparam->dns_name, EOE_DNS_NAME_LENGTH);
|
||||
data_offset += EOE_DNS_NAME_LENGTH;
|
||||
}
|
||||
|
||||
EOEp->mbxheader.length = htoes(EOE_PARAM_OFFSET + data_offset);
|
||||
EOEp->data[0] = flags;
|
||||
|
||||
/* send EoE request to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* read slave response */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, timeout);
|
||||
if (wkc > 0) /* succeeded to read slave response ? */
|
||||
{
|
||||
/* slave response should be FoE */
|
||||
if ((aEOEp->mbxheader.mbxtype & 0x0f) == ECT_MBXT_EOE)
|
||||
{
|
||||
frameinfo1 = etohs(aEOEp->frameinfo1);
|
||||
result = etohs(aEOEp->result);
|
||||
if ((EOE_HDR_FRAME_TYPE_GET(frameinfo1) != EOE_INIT_RESP) ||
|
||||
(result != EOE_RESULT_SUCCESS))
|
||||
{
|
||||
wkc = -result;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* unexpected mailbox received */
|
||||
wkc = -EC_ERR_TYPE_PACKET_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** EoE EOE get IP, blocking. Waits for response from the slave.
|
||||
*
|
||||
* @param[in] context = Context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] port = Port number on slave if applicable
|
||||
* @param[out] ipparam = IP parameter data retrived from slave
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response or returned result code
|
||||
*/
|
||||
int ecx_EOEgetIp(ecx_contextt *context, uint16 slave, uint8 port, eoe_param_t * ipparam, int timeout)
|
||||
{
|
||||
ec_EOEt *EOEp, *aEOEp;
|
||||
ec_mbxbuft MbxIn, MbxOut;
|
||||
uint16 frameinfo1, eoedatasize;
|
||||
uint8 cnt, data_offset;
|
||||
uint8 flags = 0;
|
||||
int wkc;
|
||||
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aEOEp = (ec_EOEt *)&MbxIn;
|
||||
EOEp = (ec_EOEt *)&MbxOut;
|
||||
EOEp->mbxheader.address = htoes(0x0000);
|
||||
EOEp->mbxheader.priority = 0x00;
|
||||
data_offset = EOE_PARAM_OFFSET;
|
||||
|
||||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
|
||||
EOEp->mbxheader.mbxtype = ECT_MBXT_EOE + MBX_HDR_SET_CNT(cnt); /* EoE */
|
||||
|
||||
EOEp->frameinfo1 = htoes(EOE_HDR_FRAME_TYPE_SET(EOE_GET_IP_PARAM_REQ) |
|
||||
EOE_HDR_FRAME_PORT_SET(port) |
|
||||
EOE_HDR_LAST_FRAGMENT);
|
||||
EOEp->frameinfo2 = 0;
|
||||
|
||||
EOEp->mbxheader.length = htoes(0x0004);
|
||||
EOEp->data[0] = flags;
|
||||
|
||||
/* send EoE request to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, EC_TIMEOUTTXM);
|
||||
if (wkc > 0) /* succeeded to place mailbox in slave ? */
|
||||
{
|
||||
/* clean mailboxbuffer */
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* read slave response */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, timeout);
|
||||
if (wkc > 0) /* succeeded to read slave response ? */
|
||||
{
|
||||
/* slave response should be FoE */
|
||||
if ((aEOEp->mbxheader.mbxtype & 0x0f) == ECT_MBXT_EOE)
|
||||
{
|
||||
frameinfo1 = etohs(aEOEp->frameinfo1);
|
||||
eoedatasize = etohs(aEOEp->mbxheader.length) - 0x0004;
|
||||
if (EOE_HDR_FRAME_TYPE_GET(frameinfo1) != EOE_GET_IP_PARAM_RESP)
|
||||
{
|
||||
wkc = -EOE_RESULT_UNSUPPORTED_FRAME_TYPE;
|
||||
}
|
||||
else
|
||||
{
|
||||
flags = aEOEp->data[0];
|
||||
if (flags & EOE_PARAM_MAC_INCLUDE)
|
||||
{
|
||||
memcpy(ipparam->mac.addr,
|
||||
&aEOEp->data[data_offset],
|
||||
EOE_ETHADDR_LENGTH);
|
||||
ipparam->mac_set = 1;
|
||||
data_offset += EOE_ETHADDR_LENGTH;
|
||||
}
|
||||
if (flags & EOE_PARAM_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&aEOEp->data[data_offset],
|
||||
&ipparam->ip);
|
||||
ipparam->ip_set = 1;
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (flags & EOE_PARAM_SUBNET_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&aEOEp->data[data_offset],
|
||||
&ipparam->subnet);
|
||||
ipparam->subnet_set = 1;
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (flags & EOE_PARAM_DEFAULT_GATEWAY_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&aEOEp->data[data_offset],
|
||||
&ipparam->default_gateway);
|
||||
ipparam->default_gateway_set = 1;
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (flags & EOE_PARAM_DNS_IP_INCLUDE)
|
||||
{
|
||||
EOE_ip_byte_to_uint32(&aEOEp->data[data_offset],
|
||||
&ipparam->dns_ip);
|
||||
ipparam->dns_ip_set = 1;
|
||||
data_offset += EOE_IP4_LENGTH;
|
||||
}
|
||||
if (flags & EOE_PARAM_DNS_NAME_INCLUDE)
|
||||
{
|
||||
uint16_t dns_len;
|
||||
if ((eoedatasize - data_offset) < EOE_DNS_NAME_LENGTH)
|
||||
{
|
||||
dns_len = (eoedatasize - data_offset);
|
||||
}
|
||||
else
|
||||
{
|
||||
dns_len = EOE_DNS_NAME_LENGTH;
|
||||
}
|
||||
/* Assume ZERO terminated string */
|
||||
memcpy(ipparam->dns_name, &aEOEp->data[data_offset], dns_len);
|
||||
ipparam->dns_name_set = 1;
|
||||
data_offset += EOE_DNS_NAME_LENGTH;
|
||||
}
|
||||
/* Something os not correct, flag the error */
|
||||
if(data_offset > eoedatasize)
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_MBX_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* unexpected mailbox received */
|
||||
wkc = -EC_ERR_TYPE_PACKET_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** EoE ethernet buffer write, blocking.
|
||||
*
|
||||
* If the buffer is larger than the mailbox size then the buffer is sent in
|
||||
* several fragments. The function will split the buf data in fragments and
|
||||
* send them to the slave one by one.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] port = Port number on slave if applicable
|
||||
* @param[in] psize = Size in bytes of parameter buffer.
|
||||
* @param[in] p = Pointer to parameter buffer
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave transmission
|
||||
*/
|
||||
int ecx_EOEsend(ecx_contextt *context, uint16 slave, uint8 port, int psize, void *p, int timeout)
|
||||
{
|
||||
ec_EOEt *EOEp;
|
||||
ec_mbxbuft MbxOut;
|
||||
uint16 frameinfo1, frameinfo2;
|
||||
uint8 cnt, txfragmentno;
|
||||
boolean NotLast;
|
||||
int wkc, maxdata, txframesize, txframeoffset;
|
||||
const uint8 * buf = p;
|
||||
static uint8_t txframeno = 0;
|
||||
|
||||
ec_clearmbx(&MbxOut);
|
||||
EOEp = (ec_EOEt *)&MbxOut;
|
||||
EOEp->mbxheader.address = htoes(0x0000);
|
||||
EOEp->mbxheader.priority = 0x00;
|
||||
/* data section=mailbox size - 6 mbx - 4 EoEh */
|
||||
maxdata = context->slavelist[slave].mbx_l - 0x0A;
|
||||
txframesize = psize;
|
||||
txfragmentno = 0;
|
||||
txframeoffset = 0;
|
||||
NotLast = TRUE;
|
||||
|
||||
do
|
||||
{
|
||||
txframesize = psize - txframeoffset;
|
||||
if (txframesize > maxdata)
|
||||
{
|
||||
/* Adjust to even 32-octect blocks */
|
||||
txframesize = ((maxdata >> 5) << 5);
|
||||
}
|
||||
|
||||
if (txframesize == (psize - txframeoffset))
|
||||
{
|
||||
frameinfo1 = (EOE_HDR_LAST_FRAGMENT_SET(1) | EOE_HDR_FRAME_PORT_SET(port));
|
||||
NotLast = FALSE;
|
||||
}
|
||||
else
|
||||
{
|
||||
frameinfo1 = EOE_HDR_FRAME_PORT_SET(port);
|
||||
}
|
||||
|
||||
frameinfo2 = EOE_HDR_FRAG_NO_SET(txfragmentno);
|
||||
if (txfragmentno > 0)
|
||||
{
|
||||
frameinfo2 = frameinfo2 | (EOE_HDR_FRAME_OFFSET_SET((txframeoffset >> 5)));
|
||||
}
|
||||
else
|
||||
{
|
||||
frameinfo2 = frameinfo2 | (EOE_HDR_FRAME_OFFSET_SET(((psize + 31) >> 5)));
|
||||
txframeno++;
|
||||
}
|
||||
frameinfo2 = frameinfo2 | EOE_HDR_FRAME_NO_SET(txframeno);
|
||||
|
||||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
|
||||
EOEp->mbxheader.length = htoes((uint16)(4 + txframesize)); /* no timestamp */
|
||||
EOEp->mbxheader.mbxtype = ECT_MBXT_EOE + MBX_HDR_SET_CNT(cnt); /* EoE */
|
||||
|
||||
EOEp->frameinfo1 = htoes(frameinfo1);
|
||||
EOEp->frameinfo2 = htoes(frameinfo2);
|
||||
|
||||
memcpy(EOEp->data, &buf[txframeoffset], txframesize);
|
||||
|
||||
/* send EoE request to slave */
|
||||
wkc = ecx_mbxsend(context, slave, (ec_mbxbuft *)&MbxOut, timeout);
|
||||
if ((NotLast == TRUE) && (wkc > 0))
|
||||
{
|
||||
txframeoffset += txframesize;
|
||||
txfragmentno++;
|
||||
}
|
||||
} while ((NotLast == TRUE) && (wkc > 0));
|
||||
|
||||
return wkc;
|
||||
}
|
||||
|
||||
|
||||
/** EoE ethernet buffer read, blocking.
|
||||
*
|
||||
* If the buffer is larger than the mailbox size then the buffer is received
|
||||
* by several fragments. The function will assamble the fragments into
|
||||
* a complete Ethernet buffer.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] port = Port number on slave if applicable
|
||||
* @param[in,out] psize = Size in bytes of parameter buffer.
|
||||
* @param[in] p = Pointer to parameter buffer
|
||||
* @param[in] timeout = Timeout in us, standard is EC_TIMEOUTRXM
|
||||
* @return Workcounter from last slave response or error code
|
||||
*/
|
||||
int ecx_EOErecv(ecx_contextt *context, uint16 slave, uint8 port, int * psize, void *p, int timeout)
|
||||
{
|
||||
ec_EOEt *aEOEp;
|
||||
ec_mbxbuft MbxIn;
|
||||
uint16 frameinfo1, frameinfo2;
|
||||
uint8 rxfragmentno, rxframeno;
|
||||
boolean NotLast;
|
||||
int wkc, buffersize, rxframesize, rxframeoffset, eoedatasize;
|
||||
uint8 * buf = p;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
aEOEp = (ec_EOEt *)&MbxIn;
|
||||
NotLast = TRUE;
|
||||
buffersize = *psize;
|
||||
rxfragmentno = 0;
|
||||
|
||||
/* Hang for a while if nothing is in */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, timeout);
|
||||
|
||||
while ((wkc > 0) && (NotLast == TRUE))
|
||||
{
|
||||
/* slave response should be FoE */
|
||||
if ((aEOEp->mbxheader.mbxtype & 0x0f) == ECT_MBXT_EOE)
|
||||
{
|
||||
|
||||
eoedatasize = etohs(aEOEp->mbxheader.length) - 0x00004;
|
||||
frameinfo1 = etohs(aEOEp->frameinfo1);
|
||||
frameinfo2 = etohs(aEOEp->frameinfo2);
|
||||
|
||||
if (rxfragmentno != EOE_HDR_FRAG_NO_GET(frameinfo2))
|
||||
{
|
||||
if (EOE_HDR_FRAG_NO_GET(frameinfo2) > 0)
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
/* Exit here*/
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (rxfragmentno == 0)
|
||||
{
|
||||
rxframeoffset = 0;
|
||||
rxframeno = EOE_HDR_FRAME_NO_GET(frameinfo2);
|
||||
rxframesize = (EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5);
|
||||
if (rxframesize > buffersize)
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
/* Exit here*/
|
||||
break;
|
||||
}
|
||||
if (port != EOE_HDR_FRAME_PORT_GET(frameinfo1))
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
/* Exit here*/
|
||||
break;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (rxframeno != EOE_HDR_FRAME_NO_GET(frameinfo2))
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
/* Exit here*/
|
||||
break;
|
||||
}
|
||||
else if (rxframeoffset != (EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5))
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
/* Exit here*/
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if ((rxframeoffset + eoedatasize) <= buffersize)
|
||||
{
|
||||
memcpy(&buf[rxframeoffset], aEOEp->data, eoedatasize);
|
||||
rxframeoffset += eoedatasize;
|
||||
rxfragmentno++;
|
||||
}
|
||||
|
||||
if (EOE_HDR_LAST_FRAGMENT_GET(frameinfo1))
|
||||
{
|
||||
/* Remove timestamp */
|
||||
if (EOE_HDR_TIME_APPEND_GET(frameinfo1))
|
||||
{
|
||||
rxframeoffset -= 4;
|
||||
}
|
||||
NotLast = FALSE;
|
||||
*psize = rxframeoffset;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* Hang for a while if nothing is in */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, timeout);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* unexpected mailbox received */
|
||||
wkc = -EC_ERR_TYPE_PACKET_ERROR;
|
||||
}
|
||||
}
|
||||
return wkc;
|
||||
}
|
||||
|
||||
/** EoE mailbox fragment read
|
||||
*
|
||||
* Will take the data in incoming mailbox buffer and copy to destination
|
||||
* Ethernet frame buffer at given offset and update current fragment variables
|
||||
*
|
||||
* @param[in] MbxIn = Received mailbox containing fragment data
|
||||
* @param[in,out] rxfragmentno = Fragment number
|
||||
* @param[in,out] rxframesize = Frame size
|
||||
* @param[in,out] rxframeoffset = Frame offset
|
||||
* @param[in,out] rxframeno = Frame number
|
||||
* @param[in,out] psize = Size in bytes of frame buffer.
|
||||
* @param[out] p = Pointer to frame buffer
|
||||
* @return 0= if fragment OK, >0 if last fragment, <0 on error
|
||||
*/
|
||||
int ecx_EOEreadfragment(
|
||||
ec_mbxbuft * MbxIn,
|
||||
uint8 * rxfragmentno,
|
||||
uint16 * rxframesize,
|
||||
uint16 * rxframeoffset,
|
||||
uint16 * rxframeno,
|
||||
int * psize,
|
||||
void *p)
|
||||
{
|
||||
uint16 frameinfo1, frameinfo2, eoedatasize;
|
||||
int wkc;
|
||||
ec_EOEt * aEOEp;
|
||||
uint8 * buf;
|
||||
|
||||
aEOEp = (ec_EOEt *)MbxIn;
|
||||
buf = p;
|
||||
wkc = 0;
|
||||
|
||||
/* slave response should be EoE */
|
||||
if ((aEOEp->mbxheader.mbxtype & 0x0f) == ECT_MBXT_EOE)
|
||||
{
|
||||
eoedatasize = etohs(aEOEp->mbxheader.length) - 0x00004;
|
||||
frameinfo1 = etohs(aEOEp->frameinfo1);
|
||||
frameinfo2 = etohs(aEOEp->frameinfo2);
|
||||
|
||||
/* Retrive fragment number, is it what we expect? */
|
||||
if (*rxfragmentno != EOE_HDR_FRAG_NO_GET(frameinfo2))
|
||||
{
|
||||
/* If expected fragment number is not 0, reset working variables */
|
||||
if (*rxfragmentno != 0)
|
||||
{
|
||||
*rxfragmentno = 0;
|
||||
*rxframesize = 0;
|
||||
*rxframeoffset = 0;
|
||||
*rxframeno = 0;
|
||||
}
|
||||
|
||||
/* If incoming fragment number is not 0 we can't recover, exit */
|
||||
if (EOE_HDR_FRAG_NO_GET(frameinfo2) > 0)
|
||||
{
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/* Is it a new frame?*/
|
||||
if (*rxfragmentno == 0)
|
||||
{
|
||||
*rxframesize = (uint16)(EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5);
|
||||
*rxframeoffset = 0;
|
||||
*rxframeno = EOE_HDR_FRAME_NO_GET(frameinfo2);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* If we're inside a frame, make sure it is the same */
|
||||
if (*rxframeno != EOE_HDR_FRAME_NO_GET(frameinfo2))
|
||||
{
|
||||
*rxfragmentno = 0;
|
||||
*rxframesize = 0;
|
||||
*rxframeoffset = 0;
|
||||
*rxframeno = 0;
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
return wkc;
|
||||
}
|
||||
else if (*rxframeoffset != (EOE_HDR_FRAME_OFFSET_GET(frameinfo2) << 5))
|
||||
{
|
||||
*rxfragmentno = 0;
|
||||
*rxframesize = 0;
|
||||
*rxframeoffset = 0;
|
||||
*rxframeno = 0;
|
||||
wkc = -EC_ERR_TYPE_EOE_INVALID_RX_DATA;
|
||||
return wkc;
|
||||
}
|
||||
}
|
||||
|
||||
/* Make sure we're inside expected frame size */
|
||||
if (((*rxframeoffset + eoedatasize) <= *rxframesize) &&
|
||||
((*rxframeoffset + eoedatasize) <= *psize))
|
||||
{
|
||||
memcpy(&buf[*rxframeoffset], aEOEp->data, eoedatasize);
|
||||
*rxframeoffset += eoedatasize;
|
||||
*rxfragmentno += 1;
|
||||
}
|
||||
|
||||
/* Is it the last fragment */
|
||||
if (EOE_HDR_LAST_FRAGMENT_GET(frameinfo1))
|
||||
{
|
||||
/* Remove timestamp */
|
||||
if (EOE_HDR_TIME_APPEND_GET(frameinfo1))
|
||||
{
|
||||
*rxframeoffset -= 4;
|
||||
}
|
||||
*psize = *rxframeoffset;
|
||||
*rxfragmentno = 0;
|
||||
*rxframesize = 0;
|
||||
*rxframeoffset = 0;
|
||||
*rxframeno = 0;
|
||||
wkc = 1;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
/* unexpected mailbox received */
|
||||
wkc = -EC_ERR_TYPE_PACKET_ERROR;
|
||||
}
|
||||
return wkc;
|
||||
}
|
|
@ -0,0 +1,211 @@
|
|||
/*
|
||||
* 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 ethercatfoe.c
|
||||
*/
|
||||
|
||||
#ifndef _ethercateoe_
|
||||
#define _ethercateoe_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <ethercattype.h>
|
||||
|
||||
/* use maximum size for EOE mailbox data */
|
||||
#define EC_MAXEOEDATA EC_MAXMBX
|
||||
|
||||
/** DNS length according to ETG 1000.6 */
|
||||
#define EOE_DNS_NAME_LENGTH 32
|
||||
/** Ethernet address length not including VLAN */
|
||||
#define EOE_ETHADDR_LENGTH 6
|
||||
/** IPv4 address length */
|
||||
#define EOE_IP4_LENGTH sizeof(uint32_t)
|
||||
|
||||
#define EOE_MAKEU32(a,b,c,d) (((uint32_t)((a) & 0xff) << 24) | \
|
||||
((uint32_t)((b) & 0xff) << 16) | \
|
||||
((uint32_t)((c) & 0xff) << 8) | \
|
||||
(uint32_t)((d) & 0xff))
|
||||
|
||||
#if !defined(EC_BIG_ENDIAN) && defined(EC_LITTLE_ENDIAN)
|
||||
|
||||
#define EOE_HTONS(x) ((((x) & 0x00ffUL) << 8) | (((x) & 0xff00UL) >> 8))
|
||||
#define EOE_NTOHS(x) EOE_HTONS(x)
|
||||
#define EOE_HTONL(x) ((((x) & 0x000000ffUL) << 24) | \
|
||||
(((x) & 0x0000ff00UL) << 8) | \
|
||||
(((x) & 0x00ff0000UL) >> 8) | \
|
||||
(((x) & 0xff000000UL) >> 24))
|
||||
#define EOE_NTOHL(x) EOE_HTONL(x)
|
||||
#else
|
||||
#define EOE_HTONS(x) (x)
|
||||
#define EOE_NTOHS(x) (x)
|
||||
#define EOE_HTONL(x) (x)
|
||||
#define EOE_NTOHL(x) (x)
|
||||
#endif /* !defined(EC_BIG_ENDIAN) && defined(EC_LITTLE_ENDIAN) */
|
||||
|
||||
/** Get one byte from the 4-byte address */
|
||||
#define eoe_ip4_addr1(ipaddr) (((const uint8_t*)(&(ipaddr)->addr))[0])
|
||||
#define eoe_ip4_addr2(ipaddr) (((const uint8_t*)(&(ipaddr)->addr))[1])
|
||||
#define eoe_ip4_addr3(ipaddr) (((const uint8_t*)(&(ipaddr)->addr))[2])
|
||||
#define eoe_ip4_addr4(ipaddr) (((const uint8_t*)(&(ipaddr)->addr))[3])
|
||||
|
||||
/** Set an IP address given by the four byte-parts */
|
||||
#define EOE_IP4_ADDR_TO_U32(ipaddr,a,b,c,d) \
|
||||
(ipaddr)->addr = EOE_HTONL(EOE_MAKEU32(a,b,c,d))
|
||||
|
||||
/** Header frame info 1 */
|
||||
#define EOE_HDR_FRAME_TYPE_OFFSET 0
|
||||
#define EOE_HDR_FRAME_TYPE (0xF << 0)
|
||||
#define EOE_HDR_FRAME_TYPE_SET(x) (((x) & 0xF) << 0)
|
||||
#define EOE_HDR_FRAME_TYPE_GET(x) (((x) >> 0) & 0xF)
|
||||
#define EOE_HDR_FRAME_PORT_OFFSET 4
|
||||
#define EOE_HDR_FRAME_PORT (0xF << 4)
|
||||
#define EOE_HDR_FRAME_PORT_SET(x) ((uint16)(((x) & 0xF) << 4))
|
||||
#define EOE_HDR_FRAME_PORT_GET(x) (((x) >> 4) & 0xF)
|
||||
#define EOE_HDR_LAST_FRAGMENT_OFFSET 8
|
||||
#define EOE_HDR_LAST_FRAGMENT (0x1 << 8)
|
||||
#define EOE_HDR_LAST_FRAGMENT_SET(x) (((x) & 0x1) << 8)
|
||||
#define EOE_HDR_LAST_FRAGMENT_GET(x) (((x) >> 8) & 0x1)
|
||||
#define EOE_HDR_TIME_APPEND_OFFSET 9
|
||||
#define EOE_HDR_TIME_APPEND (0x1 << 9)
|
||||
#define EOE_HDR_TIME_APPEND_SET(x) (((x) & 0x1) << 9)
|
||||
#define EOE_HDR_TIME_APPEND_GET(x) (((x) >> 9) & 0x1)
|
||||
#define EOE_HDR_TIME_REQUEST_OFFSET 10
|
||||
#define EOE_HDR_TIME_REQUEST (0x1 << 10)
|
||||
#define EOE_HDR_TIME_REQUEST_SET(x) (((x) & 0x1) << 10)
|
||||
#define EOE_HDR_TIME_REQUEST_GET(x) (((x) >> 10) & 0x1)
|
||||
|
||||
/** Header frame info 2 */
|
||||
#define EOE_HDR_FRAG_NO_OFFSET 0
|
||||
#define EOE_HDR_FRAG_NO (0x3F << 0)
|
||||
#define EOE_HDR_FRAG_NO_SET(x) ((uint16)(((x) & 0x3F) << 0))
|
||||
#define EOE_HDR_FRAG_NO_GET(x) (((x) >> 0) & 0x3F)
|
||||
#define EOE_HDR_FRAME_OFFSET_OFFSET 6
|
||||
#define EOE_HDR_FRAME_OFFSET (0x3F << 6)
|
||||
#define EOE_HDR_FRAME_OFFSET_SET(x) ((uint16)(((x) & 0x3F) << 6))
|
||||
#define EOE_HDR_FRAME_OFFSET_GET(x) (((x) >> 6) & 0x3F)
|
||||
#define EOE_HDR_FRAME_NO_OFFSET 12
|
||||
#define EOE_HDR_FRAME_NO (0xF << 12)
|
||||
#define EOE_HDR_FRAME_NO_SET(x) ((uint16)(((x) & 0xF) << 12))
|
||||
#define EOE_HDR_FRAME_NO_GET(x) (((x) >> 12) & 0xF)
|
||||
|
||||
/** EOE param */
|
||||
#define EOE_PARAM_OFFSET 4
|
||||
#define EOE_PARAM_MAC_INCLUDE (0x1 << 0)
|
||||
#define EOE_PARAM_IP_INCLUDE (0x1 << 1)
|
||||
#define EOE_PARAM_SUBNET_IP_INCLUDE (0x1 << 2)
|
||||
#define EOE_PARAM_DEFAULT_GATEWAY_INCLUDE (0x1 << 3)
|
||||
#define EOE_PARAM_DNS_IP_INCLUDE (0x1 << 4)
|
||||
#define EOE_PARAM_DNS_NAME_INCLUDE (0x1 << 5)
|
||||
|
||||
/** EoE frame types */
|
||||
#define EOE_FRAG_DATA 0
|
||||
#define EOE_INIT_RESP_TIMESTAMP 1
|
||||
#define EOE_INIT_REQ 2 /* Spec SET IP REQ */
|
||||
#define EOE_INIT_RESP 3 /* Spec SET IP RESP */
|
||||
#define EOE_SET_ADDR_FILTER_REQ 4
|
||||
#define EOE_SET_ADDR_FILTER_RESP 5
|
||||
#define EOE_GET_IP_PARAM_REQ 6
|
||||
#define EOE_GET_IP_PARAM_RESP 7
|
||||
#define EOE_GET_ADDR_FILTER_REQ 8
|
||||
#define EOE_GET_ADDR_FILTER_RESP 9
|
||||
|
||||
/** EoE parameter result codes */
|
||||
#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
|
||||
|
||||
|
||||
/** EOE ip4 address in network order */
|
||||
typedef struct eoe_ip4_addr {
|
||||
uint32_t addr;
|
||||
}eoe_ip4_addr_t;
|
||||
|
||||
/** EOE ethernet address */
|
||||
PACKED_BEGIN
|
||||
typedef struct PACKED eoe_ethaddr
|
||||
{
|
||||
uint8_t addr[EOE_ETHADDR_LENGTH];
|
||||
} eoe_ethaddr_t;
|
||||
PACKED_END
|
||||
|
||||
/** EoE IP request structure, storage only, no need to pack */
|
||||
typedef struct eoe_param
|
||||
{
|
||||
uint8_t mac_set : 1;
|
||||
uint8_t ip_set : 1;
|
||||
uint8_t subnet_set : 1;
|
||||
uint8_t default_gateway_set : 1;
|
||||
uint8_t dns_ip_set : 1;
|
||||
uint8_t dns_name_set : 1;
|
||||
eoe_ethaddr_t mac;
|
||||
eoe_ip4_addr_t ip;
|
||||
eoe_ip4_addr_t subnet;
|
||||
eoe_ip4_addr_t default_gateway;
|
||||
eoe_ip4_addr_t dns_ip;
|
||||
char dns_name[EOE_DNS_NAME_LENGTH];
|
||||
} eoe_param_t;
|
||||
|
||||
/** EOE structure.
|
||||
* Used to interpret EoE mailbox packets.
|
||||
*/
|
||||
PACKED_BEGIN
|
||||
typedef struct PACKED
|
||||
{
|
||||
ec_mbxheadert mbxheader;
|
||||
uint16_t frameinfo1;
|
||||
union
|
||||
{
|
||||
uint16_t frameinfo2;
|
||||
uint16_t result;
|
||||
};
|
||||
uint8 data[EC_MAXEOEDATA];
|
||||
} ec_EOEt;
|
||||
PACKED_END
|
||||
|
||||
int ecx_EOEdefinehook(ecx_contextt *context, void *hook);
|
||||
int ecx_EOEsetIp(ecx_contextt *context,
|
||||
uint16 slave,
|
||||
uint8 port,
|
||||
eoe_param_t * ipparam,
|
||||
int timeout);
|
||||
int ecx_EOEgetIp(ecx_contextt *context,
|
||||
uint16 slave,
|
||||
uint8 port,
|
||||
eoe_param_t * ipparam,
|
||||
int timeout);
|
||||
int ecx_EOEsend(ecx_contextt *context,
|
||||
uint16 slave,
|
||||
uint8 port,
|
||||
int psize,
|
||||
void *p,
|
||||
int timeout);
|
||||
int ecx_EOErecv(ecx_contextt *context,
|
||||
uint16 slave,
|
||||
uint8 port,
|
||||
int * psize,
|
||||
void *p,
|
||||
int timeout);
|
||||
int ecx_EOEreadfragment(
|
||||
ec_mbxbuft * MbxIn,
|
||||
uint8 * rxfragmentno,
|
||||
uint16 * rxframesize,
|
||||
uint16 * rxframeoffset,
|
||||
uint16 * rxframeno,
|
||||
int * psize,
|
||||
void *p);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -81,7 +81,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
|||
|
||||
buffersize = *psize;
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aFOEp = (ec_FOEt *)&MbxIn;
|
||||
|
@ -98,7 +98,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
|||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + (cnt << 4); /* FoE */
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + MBX_HDR_SET_CNT(cnt); /* FoE */
|
||||
FOEp->OpCode = ECT_FOE_READ;
|
||||
FOEp->Password = htoel(password);
|
||||
/* copy filename in mailbox */
|
||||
|
@ -138,7 +138,7 @@ int ecx_FOEread(ecx_contextt *context, uint16 slave, char *filename, uint32 pass
|
|||
/* get new mailbox count value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + (cnt << 4); /* FoE */
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + MBX_HDR_SET_CNT(cnt); /* FoE */
|
||||
FOEp->OpCode = ECT_FOE_ACK;
|
||||
FOEp->PacketNumber = htoel(packetnumber);
|
||||
/* send FoE ack to slave */
|
||||
|
@ -209,7 +209,7 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
|||
int tsize;
|
||||
|
||||
ec_clearmbx(&MbxIn);
|
||||
/* Empty slave out mailbox if something is in. Timout set to 0 */
|
||||
/* Empty slave out mailbox if something is in. Timeout set to 0 */
|
||||
wkc = ecx_mbxreceive(context, slave, (ec_mbxbuft *)&MbxIn, 0);
|
||||
ec_clearmbx(&MbxOut);
|
||||
aFOEp = (ec_FOEt *)&MbxIn;
|
||||
|
@ -227,7 +227,7 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
|||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + (cnt << 4); /* FoE */
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + MBX_HDR_SET_CNT(cnt); /* FoE */
|
||||
FOEp->OpCode = ECT_FOE_WRITE;
|
||||
FOEp->Password = htoel(password);
|
||||
/* copy filename in mailbox */
|
||||
|
@ -276,13 +276,13 @@ int ecx_FOEwrite(ecx_contextt *context, uint16 slave, char *filename, uint32 pas
|
|||
{
|
||||
dofinalzero = TRUE;
|
||||
}
|
||||
FOEp->MbxHeader.length = htoes(0x0006 + segmentdata);
|
||||
FOEp->MbxHeader.length = htoes((uint16)(0x0006 + segmentdata));
|
||||
FOEp->MbxHeader.address = htoes(0x0000);
|
||||
FOEp->MbxHeader.priority = 0x00;
|
||||
/* get new mailbox count value */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + (cnt << 4); /* FoE */
|
||||
FOEp->MbxHeader.mbxtype = ECT_MBXT_FOE + MBX_HDR_SET_CNT(cnt); /* FoE */
|
||||
FOEp->OpCode = ECT_FOE_DATA;
|
||||
sendpacket++;
|
||||
FOEp->PacketNumber = htoel(sendpacket);
|
||||
|
|
|
@ -19,9 +19,7 @@
|
|||
#include <string.h>
|
||||
#include "osal.h"
|
||||
#include "oshw.h"
|
||||
#include "ethercattype.h"
|
||||
#include "ethercatbase.h"
|
||||
#include "ethercatmain.h"
|
||||
#include "ethercat.h"
|
||||
|
||||
|
||||
/** delay in us for eeprom ready loop */
|
||||
|
@ -112,15 +110,15 @@ ecx_contextt ecx_context = {
|
|||
&ec_elist, // .elist =
|
||||
&ec_idxstack, // .idxstack =
|
||||
&EcatError, // .ecaterror =
|
||||
0, // .DCtO =
|
||||
0, // .DCl =
|
||||
&ec_DCtime, // .DCtime =
|
||||
&ec_SMcommtype[0], // .SMcommtype =
|
||||
&ec_PDOassign[0], // .PDOassign =
|
||||
&ec_PDOdesc[0], // .PDOdesc =
|
||||
&ec_SM, // .eepSM =
|
||||
&ec_FMMU, // .eepFMMU =
|
||||
NULL // .FOEhook()
|
||||
NULL, // .FOEhook()
|
||||
NULL, // .EOEhook()
|
||||
0 // .manualstatechange
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -325,7 +323,7 @@ void ecx_close(ecx_contextt *context)
|
|||
|
||||
/** Read one byte from slave EEPROM via cache.
|
||||
* If the cache location is empty then a read request is made to the slave.
|
||||
* Depending on the slave capabillities the request is 4 or 8 bytes.
|
||||
* Depending on the slave capabilities the request is 4 or 8 bytes.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] slave = slave number
|
||||
* @param[in] address = eeprom address in bytes (slave uses words)
|
||||
|
@ -334,7 +332,8 @@ void ecx_close(ecx_contextt *context)
|
|||
uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address)
|
||||
{
|
||||
uint16 configadr, eadr;
|
||||
uint64 edat;
|
||||
uint64 edat64;
|
||||
uint32 edat32;
|
||||
uint16 mapw, mapb;
|
||||
int lp,cnt;
|
||||
uint8 retval;
|
||||
|
@ -348,7 +347,7 @@ uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address)
|
|||
if (address < EC_MAXEEPBUF)
|
||||
{
|
||||
mapw = address >> 5;
|
||||
mapb = address - (mapw << 5);
|
||||
mapb = (uint16)(address - (mapw << 5));
|
||||
if (context->esimap[mapw] & (uint32)(1 << mapb))
|
||||
{
|
||||
/* byte is already in buffer */
|
||||
|
@ -360,22 +359,23 @@ uint8 ecx_siigetbyte(ecx_contextt *context, uint16 slave, uint16 address)
|
|||
configadr = context->slavelist[slave].configadr;
|
||||
ecx_eeprom2master(context, slave); /* set eeprom control to master */
|
||||
eadr = address >> 1;
|
||||
edat = ecx_readeepromFP (context, configadr, eadr, EC_TIMEOUTEEP);
|
||||
edat64 = ecx_readeepromFP (context, configadr, eadr, EC_TIMEOUTEEP);
|
||||
/* 8 byte response */
|
||||
if (context->slavelist[slave].eep_8byte)
|
||||
{
|
||||
put_unaligned64(edat, &(context->esibuf[eadr << 1]));
|
||||
put_unaligned64(edat64, &(context->esibuf[eadr << 1]));
|
||||
cnt = 8;
|
||||
}
|
||||
/* 4 byte response */
|
||||
else
|
||||
{
|
||||
put_unaligned32(edat, &(context->esibuf[eadr << 1]));
|
||||
edat32 = (uint32)edat64;
|
||||
put_unaligned32(edat32, &(context->esibuf[eadr << 1]));
|
||||
cnt = 4;
|
||||
}
|
||||
/* find bitmap location */
|
||||
mapw = eadr >> 4;
|
||||
mapb = (eadr << 1) - (mapw << 5);
|
||||
mapb = (uint16)((eadr << 1) - (mapw << 5));
|
||||
for(lp = 0 ; lp < cnt ; lp++)
|
||||
{
|
||||
/* set bitmap for each byte that is read */
|
||||
|
@ -550,7 +550,7 @@ uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM)
|
|||
a = SM->Startpos;
|
||||
w = ecx_siigetbyte(context, slave, a++);
|
||||
w += (ecx_siigetbyte(context, slave, a++) << 8);
|
||||
SM->nSM = (w / 4);
|
||||
SM->nSM = (uint8)(w / 4);
|
||||
SM->PhStart = ecx_siigetbyte(context, slave, a++);
|
||||
SM->PhStart += (ecx_siigetbyte(context, slave, a++) << 8);
|
||||
SM->Plength = ecx_siigetbyte(context, slave, a++);
|
||||
|
@ -609,7 +609,7 @@ uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint
|
|||
* @param[in] t = 0=RXPDO 1=TXPDO
|
||||
* @return mapping size in bits of PDO
|
||||
*/
|
||||
int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
uint32 ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
{
|
||||
uint16 a , w, c, e, er, Size;
|
||||
uint8 eectl = context->slavelist[slave].eep_pdi;
|
||||
|
@ -683,7 +683,7 @@ int ecx_FPRD_multi(ecx_contextt *context, int n, uint16 *configlst, ec_alstatust
|
|||
int wkc;
|
||||
uint8 idx;
|
||||
ecx_portt *port;
|
||||
int sldatapos[MAX_FPRD_MULTI];
|
||||
uint16 sldatapos[MAX_FPRD_MULTI];
|
||||
int slcnt;
|
||||
|
||||
port = context->port;
|
||||
|
@ -727,7 +727,7 @@ int ecx_readstate(ecx_contextt *context)
|
|||
boolean allslavespresent = FALSE;
|
||||
int wkc;
|
||||
|
||||
/* Try to establish the state of all slaves sending only one broadcast datargam.
|
||||
/* Try to establish the state of all slaves sending only one broadcast datagram.
|
||||
* This way a number of datagrams equal to the number of slaves will be sent only if needed.*/
|
||||
rval = 0;
|
||||
wkc = ecx_BRD(context->port, 0, ECT_REG_ALSTAT, sizeof(rval), &rval, EC_TIMEOUTRET);
|
||||
|
@ -787,7 +787,7 @@ int ecx_readstate(ecx_contextt *context)
|
|||
fslave = 1;
|
||||
do
|
||||
{
|
||||
lslave = *(context->slavecount);
|
||||
lslave = (uint16)*(context->slavecount);
|
||||
if ((lslave - fslave) >= MAX_FPRD_MULTI)
|
||||
{
|
||||
lslave = fslave + MAX_FPRD_MULTI - 1;
|
||||
|
@ -854,7 +854,7 @@ int ecx_writestate(ecx_contextt *context, uint16 slave)
|
|||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number, 0 = all slaves (only the "slavelist[0].state" is refreshed)
|
||||
* @param[in] reqstate = Requested state
|
||||
* @param[in] timeout = Timout value in us
|
||||
* @param[in] timeout = Timeout value in us
|
||||
* @return Requested state, or found state after timeout.
|
||||
*/
|
||||
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout)
|
||||
|
@ -1040,7 +1040,7 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
|
|||
ecx_mbxerror(context, slave, etohs(MBXEp->Detail));
|
||||
wkc = 0; /* prevent emergency to cascade up, it is already handled. */
|
||||
}
|
||||
else if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == 0x03)) /* CoE response? */
|
||||
else if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == ECT_MBXT_COE)) /* CoE response? */
|
||||
{
|
||||
EMp = (ec_emcyt *)mbx;
|
||||
if ((etohs(EMp->CANOpen) >> 12) == 0x01) /* Emergency request? */
|
||||
|
@ -1050,6 +1050,25 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
|
|||
wkc = 0; /* prevent emergency to cascade up, it is already handled. */
|
||||
}
|
||||
}
|
||||
else if ((wkc > 0) && ((mbxh->mbxtype & 0x0f) == ECT_MBXT_EOE)) /* EoE response? */
|
||||
{
|
||||
ec_EOEt * eoembx = (ec_EOEt *)mbx;
|
||||
uint16 frameinfo1 = etohs(eoembx->frameinfo1);
|
||||
/* All non fragment data frame types are expected to be handled by
|
||||
* slave send/receive API if the EoE hook is set
|
||||
*/
|
||||
if (EOE_HDR_FRAME_TYPE_GET(frameinfo1) == EOE_FRAG_DATA)
|
||||
{
|
||||
if (context->EOEhook)
|
||||
{
|
||||
if (context->EOEhook(context, slave, eoembx) > 0)
|
||||
{
|
||||
/* Fragment handled by EoE hook */
|
||||
wkc = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (wkc <= 0) /* read mailbox lost */
|
||||
|
@ -1077,7 +1096,8 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
|
|||
}
|
||||
else /* no read mailbox available */
|
||||
{
|
||||
wkc = 0;
|
||||
if (wkc > 0)
|
||||
wkc = EC_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1091,8 +1111,7 @@ int ecx_mbxreceive(ecx_contextt *context, uint16 slave, ec_mbxbuft *mbx, int tim
|
|||
*/
|
||||
void ecx_esidump(ecx_contextt *context, uint16 slave, uint8 *esibuf)
|
||||
{
|
||||
int address, incr;
|
||||
uint16 configadr;
|
||||
uint16 configadr, address, incr;
|
||||
uint64 *p64;
|
||||
uint16 *p16;
|
||||
uint64 edat;
|
||||
|
@ -1220,7 +1239,8 @@ int ecx_eeprom2pdi(ecx_contextt *context, uint16 slave)
|
|||
|
||||
uint16 ecx_eeprom_waitnotbusyAP(ecx_contextt *context, uint16 aiadr,uint16 *estat, int timeout)
|
||||
{
|
||||
int wkc, cnt = 0, retval = 0;
|
||||
int wkc, cnt = 0;
|
||||
uint16 retval = 0;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start(&timer, timeout);
|
||||
|
@ -1389,7 +1409,8 @@ int ecx_writeeepromAP(ecx_contextt *context, uint16 aiadr, uint16 eeproma, uint1
|
|||
|
||||
uint16 ecx_eeprom_waitnotbusyFP(ecx_contextt *context, uint16 configadr,uint16 *estat, int timeout)
|
||||
{
|
||||
int wkc, cnt = 0, retval = 0;
|
||||
int wkc, cnt = 0;
|
||||
uint16 retval = 0;
|
||||
osal_timert timer;
|
||||
|
||||
osal_timer_start(&timer, timeout);
|
||||
|
@ -1619,14 +1640,16 @@ uint32 ecx_readeeprom2(ecx_contextt *context, uint16 slave, int timeout)
|
|||
* @param[in] idx = Used datagram index.
|
||||
* @param[in] data = Pointer to process data segment.
|
||||
* @param[in] length = Length of data segment in bytes.
|
||||
* @param[in] DCO = Offset position of DC frame.
|
||||
*/
|
||||
static void ecx_pushindex(ecx_contextt *context, uint8 idx, void *data, uint16 length)
|
||||
static void ecx_pushindex(ecx_contextt *context, uint8 idx, void *data, uint16 length, uint16 DCO)
|
||||
{
|
||||
if(context->idxstack->pushed < EC_MAXBUF)
|
||||
{
|
||||
context->idxstack->idx[context->idxstack->pushed] = idx;
|
||||
context->idxstack->data[context->idxstack->pushed] = data;
|
||||
context->idxstack->length[context->idxstack->pushed] = length;
|
||||
context->idxstack->dcoffset[context->idxstack->pushed] = DCO;
|
||||
context->idxstack->pushed++;
|
||||
}
|
||||
}
|
||||
|
@ -1669,19 +1692,22 @@ static void ecx_clearindex(ecx_contextt *context) {
|
|||
* In order to recombine the slave response, a stack is used.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] group = group number
|
||||
* @param[in] use_overlap_io = flag if overlapped iomap is used
|
||||
* @return >0 if processdata is transmitted.
|
||||
*/
|
||||
static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean use_overlap_io)
|
||||
{
|
||||
uint32 LogAdr;
|
||||
uint16 w1, w2;
|
||||
int length, sublength;
|
||||
int length;
|
||||
uint16 sublength;
|
||||
uint8 idx;
|
||||
int wkc;
|
||||
uint8* data;
|
||||
boolean first=FALSE;
|
||||
uint16 currentsegment = 0;
|
||||
uint32 iomapinputoffset;
|
||||
uint16 DCO;
|
||||
|
||||
wkc = 0;
|
||||
if(context->grouplist[group].hasdc)
|
||||
|
@ -1724,22 +1750,22 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
{
|
||||
if(currentsegment == context->grouplist[group].Isegment)
|
||||
{
|
||||
sublength = context->grouplist[group].IOsegment[currentsegment++] - context->grouplist[group].Ioffset;
|
||||
sublength = (uint16)(context->grouplist[group].IOsegment[currentsegment++] - context->grouplist[group].Ioffset);
|
||||
}
|
||||
else
|
||||
{
|
||||
sublength = context->grouplist[group].IOsegment[currentsegment++];
|
||||
sublength = (uint16)context->grouplist[group].IOsegment[currentsegment++];
|
||||
}
|
||||
/* get new index */
|
||||
idx = ecx_getindex(context->port);
|
||||
w1 = LO_WORD(LogAdr);
|
||||
w2 = HI_WORD(LogAdr);
|
||||
DCO = 0;
|
||||
ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRD, idx, w1, w2, sublength, data);
|
||||
if(first)
|
||||
{
|
||||
context->DCl = sublength;
|
||||
/* FPRMW in second datagram */
|
||||
context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
DCO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
context->slavelist[context->grouplist[group].DCnext].configadr,
|
||||
ECT_REG_DCSYSTIME, sizeof(int64), context->DCtime);
|
||||
first = FALSE;
|
||||
|
@ -1747,7 +1773,7 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
/* send frame */
|
||||
ecx_outframe_red(context->port, idx);
|
||||
/* push index and data pointer on stack */
|
||||
ecx_pushindex(context, idx, data, sublength);
|
||||
ecx_pushindex(context, idx, data, sublength, DCO);
|
||||
length -= sublength;
|
||||
LogAdr += sublength;
|
||||
data += sublength;
|
||||
|
@ -1763,21 +1789,21 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
/* segment transfer if needed */
|
||||
do
|
||||
{
|
||||
sublength = context->grouplist[group].IOsegment[currentsegment++];
|
||||
sublength = (uint16)context->grouplist[group].IOsegment[currentsegment++];
|
||||
if((length - sublength) < 0)
|
||||
{
|
||||
sublength = length;
|
||||
sublength = (uint16)length;
|
||||
}
|
||||
/* get new index */
|
||||
idx = ecx_getindex(context->port);
|
||||
w1 = LO_WORD(LogAdr);
|
||||
w2 = HI_WORD(LogAdr);
|
||||
DCO = 0;
|
||||
ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LWR, idx, w1, w2, sublength, data);
|
||||
if(first)
|
||||
{
|
||||
context->DCl = sublength;
|
||||
/* FPRMW in second datagram */
|
||||
context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
DCO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
context->slavelist[context->grouplist[group].DCnext].configadr,
|
||||
ECT_REG_DCSYSTIME, sizeof(int64), context->DCtime);
|
||||
first = FALSE;
|
||||
|
@ -1785,7 +1811,7 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
/* send frame */
|
||||
ecx_outframe_red(context->port, idx);
|
||||
/* push index and data pointer on stack */
|
||||
ecx_pushindex(context, idx, data, sublength);
|
||||
ecx_pushindex(context, idx, data, sublength, DCO);
|
||||
length -= sublength;
|
||||
LogAdr += sublength;
|
||||
data += sublength;
|
||||
|
@ -1808,17 +1834,17 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
/* segment transfer if needed */
|
||||
do
|
||||
{
|
||||
sublength = context->grouplist[group].IOsegment[currentsegment++];
|
||||
sublength = (uint16)context->grouplist[group].IOsegment[currentsegment++];
|
||||
/* get new index */
|
||||
idx = ecx_getindex(context->port);
|
||||
w1 = LO_WORD(LogAdr);
|
||||
w2 = HI_WORD(LogAdr);
|
||||
DCO = 0;
|
||||
ecx_setupdatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_LRW, idx, w1, w2, sublength, data);
|
||||
if(first)
|
||||
{
|
||||
context->DCl = sublength;
|
||||
/* FPRMW in second datagram */
|
||||
context->DCtO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
DCO = ecx_adddatagram(context->port, &(context->port->txbuf[idx]), EC_CMD_FRMW, idx, FALSE,
|
||||
context->slavelist[context->grouplist[group].DCnext].configadr,
|
||||
ECT_REG_DCSYSTIME, sizeof(int64), context->DCtime);
|
||||
first = FALSE;
|
||||
|
@ -1830,7 +1856,7 @@ static int ecx_main_send_processdata(ecx_contextt *context, uint8 group, boolean
|
|||
* in the IOmap if we use an overlapping IOmap. If a regular IOmap
|
||||
* is used it should always be 0.
|
||||
*/
|
||||
ecx_pushindex(context, idx, (data + iomapinputoffset), sublength);
|
||||
ecx_pushindex(context, idx, (data + iomapinputoffset), sublength, DCO);
|
||||
length -= sublength;
|
||||
LogAdr += sublength;
|
||||
data += sublength;
|
||||
|
@ -1886,56 +1912,57 @@ int ecx_send_processdata_group(ecx_contextt *context, uint8 group)
|
|||
*/
|
||||
int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeout)
|
||||
{
|
||||
int pos, idx;
|
||||
uint8 idx;
|
||||
int pos;
|
||||
int wkc = 0, wkc2;
|
||||
uint16 le_wkc = 0;
|
||||
int valid_wkc = 0;
|
||||
int64 le_DCtime;
|
||||
boolean first = FALSE;
|
||||
ec_idxstackT *idxstack;
|
||||
ec_bufT *rxbuf;
|
||||
|
||||
if(context->grouplist[group].hasdc)
|
||||
{
|
||||
first = TRUE;
|
||||
}
|
||||
/* just to prevent compiler warning for unused group */
|
||||
wkc2 = group;
|
||||
|
||||
idxstack = context->idxstack;
|
||||
rxbuf = context->port->rxbuf;
|
||||
/* get first index */
|
||||
pos = ecx_pullindex(context);
|
||||
/* read the same number of frames as send */
|
||||
while (pos >= 0)
|
||||
{
|
||||
idx = context->idxstack->idx[pos];
|
||||
wkc2 = ecx_waitinframe(context->port, context->idxstack->idx[pos], timeout);
|
||||
idx = idxstack->idx[pos];
|
||||
wkc2 = ecx_waitinframe(context->port, idx, timeout);
|
||||
/* check if there is input data in frame */
|
||||
if (wkc2 > EC_NOFRAME)
|
||||
{
|
||||
if((context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRD) || (context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRW))
|
||||
if((rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRD) || (rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LRW))
|
||||
{
|
||||
if(first)
|
||||
if(idxstack->dcoffset[pos] > 0)
|
||||
{
|
||||
memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->DCl);
|
||||
memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
|
||||
memcpy(idxstack->data[pos], &(rxbuf[idx][EC_HEADERSIZE]), idxstack->length[pos]);
|
||||
memcpy(&le_wkc, &(rxbuf[idx][EC_HEADERSIZE + idxstack->length[pos]]), EC_WKCSIZE);
|
||||
wkc = etohs(le_wkc);
|
||||
memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
|
||||
memcpy(&le_DCtime, &(rxbuf[idx][idxstack->dcoffset[pos]]), sizeof(le_DCtime));
|
||||
*(context->DCtime) = etohll(le_DCtime);
|
||||
first = FALSE;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* copy input data back to process data buffer */
|
||||
memcpy(context->idxstack->data[pos], &(context->port->rxbuf[idx][EC_HEADERSIZE]), context->idxstack->length[pos]);
|
||||
memcpy(idxstack->data[pos], &(rxbuf[idx][EC_HEADERSIZE]), idxstack->length[pos]);
|
||||
wkc += wkc2;
|
||||
}
|
||||
valid_wkc = 1;
|
||||
}
|
||||
else if(context->port->rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LWR)
|
||||
else if(rxbuf[idx][EC_CMDOFFSET]==EC_CMD_LWR)
|
||||
{
|
||||
if(first)
|
||||
if(idxstack->dcoffset[pos] > 0)
|
||||
{
|
||||
memcpy(&le_wkc, &(context->port->rxbuf[idx][EC_HEADERSIZE + context->DCl]), EC_WKCSIZE);
|
||||
memcpy(&le_wkc, &(rxbuf[idx][EC_HEADERSIZE + idxstack->length[pos]]), EC_WKCSIZE);
|
||||
/* output WKC counts 2 times when using LRW, emulate the same for LWR */
|
||||
wkc = etohs(le_wkc) * 2;
|
||||
memcpy(&le_DCtime, &(context->port->rxbuf[idx][context->DCtO]), sizeof(le_DCtime));
|
||||
memcpy(&le_DCtime, &(rxbuf[idx][idxstack->dcoffset[pos]]), sizeof(le_DCtime));
|
||||
*(context->DCtime) = etohll(le_DCtime);
|
||||
first = FALSE;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -2103,7 +2130,7 @@ uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n)
|
|||
* @return mapping size in bits of PDO
|
||||
* @see ecx_siiPDO
|
||||
*/
|
||||
int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
uint32 ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t)
|
||||
{
|
||||
return ecx_siiPDO (&ecx_context, slave, PDO, t);
|
||||
}
|
||||
|
@ -2132,7 +2159,7 @@ int ec_writestate(uint16 slave)
|
|||
* This is a blocking function.
|
||||
* @param[in] slave = Slave number, 0 = all slaves
|
||||
* @param[in] reqstate = Requested state
|
||||
* @param[in] timeout = Timout value in us
|
||||
* @param[in] timeout = Timeout value in us
|
||||
* @return Requested state, or found state after timeout.
|
||||
* @see ecx_statecheck
|
||||
*/
|
||||
|
@ -2334,7 +2361,6 @@ int ec_send_processdata_group(uint8 group)
|
|||
* In contrast to the base LRW function this function is non-blocking.
|
||||
* If the processdata does not fit in one datagram, multiple are used.
|
||||
* In order to recombine the slave response, a stack is used.
|
||||
* @param[in] context = context struct
|
||||
* @param[in] group = group number
|
||||
* @return >0 if processdata is transmitted.
|
||||
* @see ecx_send_overlap_processdata_group
|
||||
|
|
|
@ -100,6 +100,8 @@ PACKED_END
|
|||
|
||||
#define EC_SMENABLEMASK 0xfffeffff
|
||||
|
||||
typedef struct ecx_context ecx_contextt;
|
||||
|
||||
/** for list of ethercat slaves detected */
|
||||
typedef struct ec_slave
|
||||
{
|
||||
|
@ -225,8 +227,10 @@ typedef struct ec_slave
|
|||
uint8 FMMUunused;
|
||||
/** Boolean for tracking whether the slave is (not) responding, not used/set by the SOEM library */
|
||||
boolean islost;
|
||||
/** registered configuration function PO->SO */
|
||||
/** registered configuration function PO->SO, (DEPRECATED)*/
|
||||
int (*PO2SOconfig)(uint16 slave);
|
||||
/** registered configuration function PO->SO */
|
||||
int (*PO2SOconfigx)(ecx_contextt * context, uint16 slave);
|
||||
/** readable name */
|
||||
char name[EC_MAXNAME + 1];
|
||||
} ec_slavet;
|
||||
|
@ -252,7 +256,7 @@ typedef struct ec_group
|
|||
int16 Ebuscurrent;
|
||||
/** if >0 block use of LRW in processdata */
|
||||
uint8 blockLRW;
|
||||
/** IO segegments used */
|
||||
/** IO segments used */
|
||||
uint16 nsegments;
|
||||
/** 1st input segment */
|
||||
uint16 Isegment;
|
||||
|
@ -287,9 +291,9 @@ typedef struct ec_eepromSM
|
|||
uint16 PhStart;
|
||||
uint16 Plength;
|
||||
uint8 Creg;
|
||||
uint8 Sreg; /* dont care */
|
||||
uint8 Sreg; /* don't care */
|
||||
uint8 Activate;
|
||||
uint8 PDIctrl; /* dont care */
|
||||
uint8 PDIctrl; /* don't care */
|
||||
} ec_eepromSMt;
|
||||
|
||||
/** record to store rxPDO and txPDO table from eeprom */
|
||||
|
@ -336,6 +340,7 @@ typedef struct ec_idxstack
|
|||
uint8 idx[EC_MAXBUF];
|
||||
void *data[EC_MAXBUF];
|
||||
uint16 length[EC_MAXBUF];
|
||||
uint16 dcoffset[EC_MAXBUF];
|
||||
} ec_idxstackT;
|
||||
|
||||
/** ringbuf for error storage */
|
||||
|
@ -377,7 +382,7 @@ typedef struct PACKED ec_PDOdesc
|
|||
PACKED_END
|
||||
|
||||
/** Context structure , referenced by all ecx functions*/
|
||||
typedef struct ecx_context
|
||||
struct ecx_context
|
||||
{
|
||||
/** port reference, may include red_port */
|
||||
ecx_portt *port;
|
||||
|
@ -403,10 +408,6 @@ typedef struct ecx_context
|
|||
ec_idxstackT *idxstack;
|
||||
/** reference to ecaterror state */
|
||||
boolean *ecaterror;
|
||||
/** internal, position of DC datagram in process data packet */
|
||||
uint16 DCtO;
|
||||
/** internal, length of DC datagram */
|
||||
uint16 DCl;
|
||||
/** reference to last DC time from slaves */
|
||||
int64 *DCtime;
|
||||
/** internal, SM buffer */
|
||||
|
@ -421,7 +422,11 @@ typedef struct ecx_context
|
|||
ec_eepromFMMUt *eepFMMU;
|
||||
/** registered FoE hook */
|
||||
int (*FOEhook)(uint16 slave, int packetnumber, int datasize);
|
||||
} ecx_contextt;
|
||||
/** registered EoE hook */
|
||||
int (*EOEhook)(ecx_contextt * context, uint16 slave, void * eoembx);
|
||||
/** flag to control legacy automatic state change or manual state change */
|
||||
int manualstatechange;
|
||||
};
|
||||
|
||||
#ifdef EC_VER1
|
||||
/** global struct to hold default master context */
|
||||
|
@ -448,7 +453,7 @@ void ec_siistring(char *str, uint16 slave, uint16 Sn);
|
|||
uint16 ec_siiFMMU(uint16 slave, ec_eepromFMMUt* FMMU);
|
||||
uint16 ec_siiSM(uint16 slave, ec_eepromSMt* SM);
|
||||
uint16 ec_siiSMnext(uint16 slave, ec_eepromSMt* SM, uint16 n);
|
||||
int ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t);
|
||||
uint32 ec_siiPDO(uint16 slave, ec_eepromPDOt* PDO, uint8 t);
|
||||
int ec_readstate(void);
|
||||
int ec_writestate(uint16 slave);
|
||||
uint16 ec_statecheck(uint16 slave, uint16 reqstate, int timeout);
|
||||
|
@ -491,7 +496,7 @@ void ecx_siistring(ecx_contextt *context, char *str, uint16 slave, uint16 Sn);
|
|||
uint16 ecx_siiFMMU(ecx_contextt *context, uint16 slave, ec_eepromFMMUt* FMMU);
|
||||
uint16 ecx_siiSM(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM);
|
||||
uint16 ecx_siiSMnext(ecx_contextt *context, uint16 slave, ec_eepromSMt* SM, uint16 n);
|
||||
int ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t);
|
||||
uint32 ecx_siiPDO(ecx_contextt *context, uint16 slave, ec_eepromPDOt* PDO, uint8 t);
|
||||
int ecx_readstate(ecx_contextt *context);
|
||||
int ecx_writestate(ecx_contextt *context, uint16 slave);
|
||||
uint16 ecx_statecheck(ecx_contextt *context, uint16 slave, uint16 reqstate, int timeout);
|
||||
|
@ -514,6 +519,7 @@ int ecx_receive_processdata_group(ecx_contextt *context, uint8 group, int timeou
|
|||
int ecx_send_processdata(ecx_contextt *context);
|
||||
int ecx_send_overlap_processdata(ecx_contextt *context);
|
||||
int ecx_receive_processdata(ecx_contextt *context, int timeout);
|
||||
int ecx_send_processdata_group(ecx_contextt *context, uint8 group);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
* Module to convert EtherCAT errors to readable messages.
|
||||
*
|
||||
* SDO abort messages and AL status codes are used to relay slave errors to
|
||||
* the user application. This module converts the binary codes to readble text.
|
||||
* the user application. This module converts the binary codes to readable text.
|
||||
* For the defined error codes see the EtherCAT protocol documentation.
|
||||
*/
|
||||
|
||||
|
@ -215,7 +215,7 @@ const ec_mbxerrorlist_t ec_mbxerrorlist[] = {
|
|||
{0x0005, "Invalid mailbox header"},
|
||||
{0x0006, "Length of received mailbox data is too short"},
|
||||
{0x0007, "No more memory in slave"},
|
||||
{0x0008, "The lenght of data is inconsistent"},
|
||||
{0x0008, "The length of data is inconsistent"},
|
||||
{0xffff, "Unknown"}
|
||||
};
|
||||
|
||||
|
@ -291,6 +291,63 @@ char* ec_mbxerror2string( uint16 errorcode)
|
|||
return (char *) ec_mbxerrorlist[i].errordescription;
|
||||
}
|
||||
|
||||
/** Convert an error to text string.
|
||||
*
|
||||
* @param[in] Ec = Struct describing the error.
|
||||
* @return readable string
|
||||
*/
|
||||
char* ecx_err2string(const ec_errort Ec)
|
||||
{
|
||||
char timestr[20];
|
||||
sprintf(timestr, "Time:%12.3f", Ec.Time.sec + (Ec.Time.usec / 1000000.0) );
|
||||
switch (Ec.Etype)
|
||||
{
|
||||
case EC_ERR_TYPE_SDO_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_EMERGENCY:
|
||||
{
|
||||
sprintf(estring, "%s EMERGENCY slave:%d error:%4.4x\n",
|
||||
timestr, Ec.Slave, Ec.ErrorCode);
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_PACKET_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s PACKET slave:%d index:%4.4x.%2.2x error:%d\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, Ec.ErrorCode);
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_SDOINFO_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_SOE_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SoE slave:%d IDN:%4.4x error:%4.4x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, (unsigned)Ec.AbortCode, ec_soeerror2string(Ec.ErrorCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_MBX_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s MBX slave:%d error:%4.4x %s\n",
|
||||
timestr, Ec.Slave, Ec.ErrorCode, ec_mbxerror2string(Ec.ErrorCode));
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
sprintf(estring, "%s error:%8.8x\n",
|
||||
timestr, (unsigned)Ec.AbortCode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
return (char*) estring;
|
||||
}
|
||||
|
||||
/** Look up error in ec_errorlist and convert to text string.
|
||||
*
|
||||
* @param[in] context = context struct
|
||||
|
@ -299,57 +356,10 @@ char* ec_mbxerror2string( uint16 errorcode)
|
|||
char* ecx_elist2string(ecx_contextt *context)
|
||||
{
|
||||
ec_errort Ec;
|
||||
char timestr[20];
|
||||
|
||||
if (ecx_poperror(context, &Ec))
|
||||
{
|
||||
sprintf(timestr, "Time:%12.3f", Ec.Time.sec + (Ec.Time.usec / 1000000.0) );
|
||||
switch (Ec.Etype)
|
||||
{
|
||||
case EC_ERR_TYPE_SDO_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_EMERGENCY:
|
||||
{
|
||||
sprintf(estring, "%s EMERGENCY slave:%d error:%4.4x\n",
|
||||
timestr, Ec.Slave, Ec.ErrorCode);
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_PACKET_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s PACKET slave:%d index:%4.4x.%2.2x error:%d\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, Ec.ErrorCode);
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_SDOINFO_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SDO slave:%d index:%4.4x.%2.2x error:%8.8x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, Ec.SubIdx, (unsigned)Ec.AbortCode, ec_sdoerror2string(Ec.AbortCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_SOE_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s SoE slave:%d IDN:%4.4x error:%4.4x %s\n",
|
||||
timestr, Ec.Slave, Ec.Index, (unsigned)Ec.AbortCode, ec_soeerror2string(Ec.ErrorCode));
|
||||
break;
|
||||
}
|
||||
case EC_ERR_TYPE_MBX_ERROR:
|
||||
{
|
||||
sprintf(estring, "%s MBX slave:%d error:%4.4x %s\n",
|
||||
timestr, Ec.Slave, Ec.ErrorCode, ec_mbxerror2string(Ec.ErrorCode));
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
sprintf(estring, "%s error:%8.8x\n",
|
||||
timestr, (unsigned)Ec.AbortCode);
|
||||
break;
|
||||
}
|
||||
}
|
||||
return (char*) estring;
|
||||
return ecx_err2string(Ec);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
|
|
@ -19,6 +19,8 @@ extern "C"
|
|||
char* ec_sdoerror2string( uint32 sdoerrorcode);
|
||||
char* ec_ALstatuscode2string( uint16 ALstatuscode);
|
||||
char* ec_soeerror2string( uint16 errorcode);
|
||||
char* ec_mbxerror2string( uint16 errorcode);
|
||||
char* ecx_err2string(const ec_errort Ec);
|
||||
char* ecx_elist2string(ecx_contextt *context);
|
||||
|
||||
#ifdef EC_VER1
|
||||
|
|
|
@ -68,7 +68,7 @@ void ecx_SoEerror(ecx_contextt *context, uint16 Slave, uint16 idn, uint16 Error)
|
|||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] driveNo = Drive number in slave
|
||||
* @param[in] elementflags = Flags to select what properties of IDN are to be transfered.
|
||||
* @param[in] elementflags = Flags to select what properties of IDN are to be transferred.
|
||||
* @param[in] idn = IDN.
|
||||
* @param[in,out] psize = Size in bytes of parameter buffer, returns bytes read from SoE.
|
||||
* @param[out] p = Pointer to parameter buffer
|
||||
|
@ -78,7 +78,7 @@ void ecx_SoEerror(ecx_contextt *context, uint16 Slave, uint16 idn, uint16 Error)
|
|||
int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int *psize, void *p, int timeout)
|
||||
{
|
||||
ec_SoEt *SoEp, *aSoEp;
|
||||
uint16 totalsize, framedatasize;
|
||||
int totalsize, framedatasize;
|
||||
int wkc;
|
||||
uint8 *bp;
|
||||
uint8 *mp;
|
||||
|
@ -99,7 +99,7 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
|||
/* get new mailbox count value, used as session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
SoEp->MbxHeader.mbxtype = ECT_MBXT_SOE + (cnt << 4); /* SoE */
|
||||
SoEp->MbxHeader.mbxtype = ECT_MBXT_SOE + MBX_HDR_SET_CNT(cnt); /* SoE */
|
||||
SoEp->opCode = ECT_SOE_READREQ;
|
||||
SoEp->incomplete = 0;
|
||||
SoEp->error = 0;
|
||||
|
@ -190,7 +190,7 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
|||
* @param[in] context = context struct
|
||||
* @param[in] slave = Slave number
|
||||
* @param[in] driveNo = Drive number in slave
|
||||
* @param[in] elementflags = Flags to select what properties of IDN are to be transfered.
|
||||
* @param[in] elementflags = Flags to select what properties of IDN are to be transferred.
|
||||
* @param[in] idn = IDN.
|
||||
* @param[in] psize = Size in bytes of parameter buffer.
|
||||
* @param[out] p = Pointer to parameter buffer
|
||||
|
@ -200,7 +200,7 @@ int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elemen
|
|||
int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int psize, void *p, int timeout)
|
||||
{
|
||||
ec_SoEt *SoEp, *aSoEp;
|
||||
uint16 framedatasize, maxdata;
|
||||
int framedatasize, maxdata;
|
||||
int wkc;
|
||||
uint8 *mp;
|
||||
uint8 *hp;
|
||||
|
@ -236,13 +236,13 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
|||
framedatasize = maxdata; /* segmented transfer needed */
|
||||
NotLast = TRUE;
|
||||
SoEp->incomplete = 1;
|
||||
SoEp->fragmentsleft = psize / maxdata;
|
||||
SoEp->fragmentsleft = (uint16)(psize / maxdata);
|
||||
}
|
||||
SoEp->MbxHeader.length = htoes(sizeof(ec_SoEt) - sizeof(ec_mbxheadert) + framedatasize);
|
||||
SoEp->MbxHeader.length = htoes((uint16)(sizeof(ec_SoEt) - sizeof(ec_mbxheadert) + framedatasize));
|
||||
/* get new mailbox counter, used for session handle */
|
||||
cnt = ec_nextmbxcnt(context->slavelist[slave].mbx_cnt);
|
||||
context->slavelist[slave].mbx_cnt = cnt;
|
||||
SoEp->MbxHeader.mbxtype = ECT_MBXT_SOE + (cnt << 4); /* SoE */
|
||||
SoEp->MbxHeader.mbxtype = ECT_MBXT_SOE + MBX_HDR_SET_CNT(cnt); /* SoE */
|
||||
/* copy parameter data to mailbox */
|
||||
memcpy(mp, hp, framedatasize);
|
||||
hp += framedatasize;
|
||||
|
@ -307,14 +307,14 @@ int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 eleme
|
|||
* @param[in] slave = Slave number
|
||||
* @param[out] Osize = Size in bits of output mapping (MTD) found
|
||||
* @param[out] Isize = Size in bits of input mapping (AT) found
|
||||
* @return >0 if mapping succesful.
|
||||
* @return >0 if mapping successful.
|
||||
*/
|
||||
int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
||||
int ecx_readIDNmap(ecx_contextt *context, uint16 slave, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
int retVal = 0;
|
||||
int wkc;
|
||||
int psize;
|
||||
int driveNr;
|
||||
uint8 driveNr;
|
||||
uint16 entries, itemcount;
|
||||
ec_SoEmappingt SoEmapping;
|
||||
ec_SoEattributet SoEattribute;
|
||||
|
@ -329,7 +329,7 @@ int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
|||
if ((wkc > 0) && (psize >= 4) && ((entries = etohs(SoEmapping.currentlength) / 2) > 0) && (entries <= EC_SOE_MAXMAPPING))
|
||||
{
|
||||
/* command word (uint16) is always mapped but not in list */
|
||||
*Osize = 16;
|
||||
*Osize += 16;
|
||||
for (itemcount = 0 ; itemcount < entries ; itemcount++)
|
||||
{
|
||||
psize = sizeof(SoEattribute);
|
||||
|
@ -348,7 +348,7 @@ int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize)
|
|||
if ((wkc > 0) && (psize >= 4) && ((entries = etohs(SoEmapping.currentlength) / 2) > 0) && (entries <= EC_SOE_MAXMAPPING))
|
||||
{
|
||||
/* status word (uint16) is always mapped but not in list */
|
||||
*Isize = 16;
|
||||
*Isize += 16;
|
||||
for (itemcount = 0 ; itemcount < entries ; itemcount++)
|
||||
{
|
||||
psize = sizeof(SoEattribute);
|
||||
|
@ -382,7 +382,7 @@ int ec_SoEwrite(uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int
|
|||
return ecx_SoEwrite(&ecx_context, slave, driveNo, elementflags, idn, psize, p, timeout);
|
||||
}
|
||||
|
||||
int ec_readIDNmap(uint16 slave, int *Osize, int *Isize)
|
||||
int ec_readIDNmap(uint16 slave, uint32 *Osize, uint32 *Isize)
|
||||
{
|
||||
return ecx_readIDNmap(&ecx_context, slave, Osize, Isize);
|
||||
}
|
||||
|
|
|
@ -116,12 +116,12 @@ PACKED_END
|
|||
#ifdef EC_VER1
|
||||
int ec_SoEread(uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int *psize, void *p, int timeout);
|
||||
int ec_SoEwrite(uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int psize, void *p, int timeout);
|
||||
int ec_readIDNmap(uint16 slave, int *Osize, int *Isize);
|
||||
int ec_readIDNmap(uint16 slave, uint32 *Osize, uint32 *Isize);
|
||||
#endif
|
||||
|
||||
int ecx_SoEread(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int *psize, void *p, int timeout);
|
||||
int ecx_SoEwrite(ecx_contextt *context, uint16 slave, uint8 driveNo, uint8 elementflags, uint16 idn, int psize, void *p, int timeout);
|
||||
int ecx_readIDNmap(ecx_contextt *context, uint16 slave, int *Osize, int *Isize);
|
||||
int ecx_readIDNmap(ecx_contextt *context, uint16 slave, uint32 *Osize, uint32 *Isize);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
|
|
@ -23,21 +23,30 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
/** Define Little or Big endian target */
|
||||
#define EC_LITTLE_ENDIAN
|
||||
|
||||
/** define EC_VER1 if version 1 default context and functions are needed
|
||||
* comment if application uses only ecx_ functions and own context */
|
||||
#define EC_VER1
|
||||
|
||||
#include "osal.h"
|
||||
|
||||
/** return value general error */
|
||||
#define EC_ERROR -3
|
||||
/** define EC_VER1 if version 1 default context and functions are needed
|
||||
* define EC_VER2 if application uses only ecx_ functions and own context */
|
||||
#if !defined(EC_VER1) && !defined(EC_VER2)
|
||||
# define EC_VER1
|
||||
#endif
|
||||
|
||||
|
||||
/** Define little endian target by default if no endian is set */
|
||||
#if !defined(EC_LITTLE_ENDIAN) && !defined(EC_BIG_ENDIAN)
|
||||
# define EC_LITTLE_ENDIAN
|
||||
#endif
|
||||
|
||||
/** return value no frame returned */
|
||||
#define EC_NOFRAME -1
|
||||
#define EC_NOFRAME -1
|
||||
/** return value unknown frame received */
|
||||
#define EC_OTHERFRAME -2
|
||||
#define EC_OTHERFRAME -2
|
||||
/** return value general error */
|
||||
#define EC_ERROR -3
|
||||
/** return value too many slaves */
|
||||
#define EC_SLAVECOUNTEXCEEDED -4
|
||||
/** return value request timeout */
|
||||
#define EC_TIMEOUT -5
|
||||
/** maximum EtherCAT frame length in bytes */
|
||||
#define EC_MAXECATFRAME 1518
|
||||
/** maximum EtherCAT LRW frame length in bytes */
|
||||
|
@ -71,6 +80,8 @@ extern "C"
|
|||
#define EC_MAXEEPBUF EC_MAXEEPBITMAP << 5
|
||||
/** default number of retries if wkc <= 0 */
|
||||
#define EC_DEFAULTRETRIES 3
|
||||
/** default group size in 2^x */
|
||||
#define EC_LOGGROUPOFFSET 16
|
||||
|
||||
/** definition for frame buffers */
|
||||
typedef uint8 ec_bufT[EC_BUFSIZE];
|
||||
|
@ -450,16 +461,17 @@ enum
|
|||
/** Error types */
|
||||
typedef enum
|
||||
{
|
||||
EC_ERR_TYPE_SDO_ERROR = 0,
|
||||
EC_ERR_TYPE_EMERGENCY = 1,
|
||||
EC_ERR_TYPE_PACKET_ERROR = 3,
|
||||
EC_ERR_TYPE_SDOINFO_ERROR = 4,
|
||||
EC_ERR_TYPE_FOE_ERROR = 5,
|
||||
EC_ERR_TYPE_FOE_BUF2SMALL = 6,
|
||||
EC_ERR_TYPE_FOE_PACKETNUMBER = 7,
|
||||
EC_ERR_TYPE_SOE_ERROR = 8,
|
||||
EC_ERR_TYPE_MBX_ERROR = 9,
|
||||
EC_ERR_TYPE_FOE_FILE_NOTFOUND = 10
|
||||
EC_ERR_TYPE_SDO_ERROR = 0,
|
||||
EC_ERR_TYPE_EMERGENCY = 1,
|
||||
EC_ERR_TYPE_PACKET_ERROR = 3,
|
||||
EC_ERR_TYPE_SDOINFO_ERROR = 4,
|
||||
EC_ERR_TYPE_FOE_ERROR = 5,
|
||||
EC_ERR_TYPE_FOE_BUF2SMALL = 6,
|
||||
EC_ERR_TYPE_FOE_PACKETNUMBER = 7,
|
||||
EC_ERR_TYPE_SOE_ERROR = 8,
|
||||
EC_ERR_TYPE_MBX_ERROR = 9,
|
||||
EC_ERR_TYPE_FOE_FILE_NOTFOUND = 10,
|
||||
EC_ERR_TYPE_EOE_INVALID_RX_DATA = 11
|
||||
} ec_err_type;
|
||||
|
||||
/** Struct to retrieve errors. */
|
||||
|
@ -494,6 +506,10 @@ typedef struct
|
|||
} ec_errort;
|
||||
|
||||
/** Helper macros */
|
||||
|
||||
/** Set the count value in the Mailbox header */
|
||||
#define MBX_HDR_SET_CNT(cnt) ((uint8)((cnt) << 4))
|
||||
|
||||
/** Macro to make a word from 2 bytes */
|
||||
#define MK_WORD(msb, lsb) ((((uint16)(msb))<<8) | (lsb))
|
||||
/** Macro to get hi byte of a word */
|
||||
|
|
|
@ -404,7 +404,7 @@ int main(int argc, char *argv[])
|
|||
if ((strncmp(argv[3], "-walias", sizeof("-walias")) == 0))
|
||||
{
|
||||
mode = MODE_WRITEALIAS;
|
||||
alias = atoi(argv(4));
|
||||
alias = atoi(argv[4]);
|
||||
}
|
||||
}
|
||||
/* start tool */
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#include "ethercat.h"
|
||||
|
||||
#define MAXBUF 32768
|
||||
#define MAXBUF 524288
|
||||
#define STDBUF 2048
|
||||
#define MINBUF 128
|
||||
#define CRCBUF 14
|
||||
|
|
|
@ -0,0 +1,420 @@
|
|||
/** \file
|
||||
* \brief Example code for Simple Open EtherCAT master EoE
|
||||
*
|
||||
* This example will run the follwing EoE functions
|
||||
* SetIP
|
||||
* GetIP
|
||||
*
|
||||
* Loop
|
||||
* Send fragment data (Layer 2 0x88A4)
|
||||
* Receive fragment data (Layer 2 0x88A4)
|
||||
*
|
||||
* For this to work, a special slave test code is running that
|
||||
* will bounce the sent 0x88A4 back to receive.
|
||||
*
|
||||
* Usage : eoe_test [ifname1]
|
||||
* ifname is NIC interface, f.e. eth0
|
||||
*
|
||||
* This is a minimal test.
|
||||
*
|
||||
* (c)Arthur Ketels 2010 - 2011
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <inttypes.h>
|
||||
|
||||
#include "ethercat.h"
|
||||
|
||||
#define EC_TIMEOUTMON 500
|
||||
|
||||
char IOmap[4096];
|
||||
|
||||
int expectedWKC;
|
||||
boolean needlf;
|
||||
volatile int globalwkc;
|
||||
boolean inOP;
|
||||
uint8 currentgroup = 0;
|
||||
OSAL_THREAD_HANDLE thread1;
|
||||
OSAL_THREAD_HANDLE thread2;
|
||||
uint8 txbuf[1024];
|
||||
|
||||
/** Current RX fragment number */
|
||||
uint8_t rxfragmentno = 0;
|
||||
/** Complete RX frame size of current frame */
|
||||
uint16_t rxframesize = 0;
|
||||
/** Current RX data offset in frame */
|
||||
uint16_t rxframeoffset = 0;
|
||||
/** Current RX frame number */
|
||||
uint16_t rxframeno = 0;
|
||||
uint8 rxbuf[1024];
|
||||
int size_of_rx = sizeof(rxbuf);
|
||||
|
||||
/** registered EoE hook */
|
||||
int eoe_hook(ecx_contextt * context, uint16 slave, void * eoembx)
|
||||
{
|
||||
int wkc;
|
||||
/* Pass received Mbx data to EoE recevive fragment function that
|
||||
* that will start/continue fill an Ethernet frame buffer
|
||||
*/
|
||||
size_of_rx = sizeof(rxbuf);
|
||||
wkc = ecx_EOEreadfragment(eoembx,
|
||||
&rxfragmentno,
|
||||
&rxframesize,
|
||||
&rxframeoffset,
|
||||
&rxframeno,
|
||||
&size_of_rx,
|
||||
rxbuf);
|
||||
|
||||
printf("Read frameno %d, fragmentno %d\n", rxframeno, rxfragmentno);
|
||||
|
||||
/* wkc == 1 would mean a frame is complete , last fragment flag have been set and all
|
||||
* other checks must have past
|
||||
*/
|
||||
if (wkc > 0)
|
||||
{
|
||||
ec_etherheadert *bp = (ec_etherheadert *)rxbuf;
|
||||
uint16 type = ntohs(bp->etype);
|
||||
printf("Frameno %d, type 0x%x complete\n", rxframeno, type);
|
||||
if (type == ETH_P_ECAT)
|
||||
{
|
||||
/* Sanity check that received buffer still is OK */
|
||||
if (sizeof(txbuf) != size_of_rx)
|
||||
{
|
||||
printf("Size differs, expected %d , received %d\n", sizeof(txbuf), size_of_rx);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Size OK, expected %d , received %d\n", sizeof(txbuf), size_of_rx);
|
||||
}
|
||||
/* Check that the TX and RX frames are EQ */
|
||||
if (memcmp(rxbuf, txbuf, size_of_rx))
|
||||
{
|
||||
printf("memcmp result != 0\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("memcmp result == 0\n");
|
||||
}
|
||||
/* Send a new frame */
|
||||
int ixme;
|
||||
for (ixme = ETH_HEADERSIZE; ixme < sizeof(txbuf); ixme++)
|
||||
{
|
||||
txbuf[ixme] = (uint8)rand();
|
||||
}
|
||||
printf("Send a new frame\n");
|
||||
ecx_EOEsend(context, 1, 0, sizeof(txbuf), txbuf, EC_TIMEOUTRXM);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Skip type 0x%x\n", type);
|
||||
}
|
||||
}
|
||||
/* No point in returning as unhandled */
|
||||
return 1;
|
||||
}
|
||||
|
||||
OSAL_THREAD_FUNC mailbox_reader(void *lpParam)
|
||||
{
|
||||
ecx_contextt *context = (ecx_contextt *)lpParam;
|
||||
int wkc;
|
||||
ec_mbxbuft MbxIn;
|
||||
ec_mbxheadert * MbxHdr = (ec_mbxheadert *)MbxIn;
|
||||
|
||||
int ixme;
|
||||
ec_setupheader(&txbuf);
|
||||
for (ixme = ETH_HEADERSIZE; ixme < sizeof(txbuf); ixme++)
|
||||
{
|
||||
txbuf[ixme] = (uint8)rand();
|
||||
}
|
||||
/* Send a made up frame to trigger a fragmented transfer
|
||||
* Used with a special bound impelmentaion of SOES. Will
|
||||
* trigger a fragmented transfer back of the same frame.
|
||||
*/
|
||||
ecx_EOEsend(context, 1, 0, sizeof(txbuf), txbuf, EC_TIMEOUTRXM);
|
||||
|
||||
for (;;)
|
||||
{
|
||||
/* Read mailbox if no other mailbox conversation is ongoing eg. SDOwrite/SDOwrite etc.*/
|
||||
wkc = ecx_mbxreceive(context, 1, (ec_mbxbuft *)&MbxIn, 0);
|
||||
if (wkc > 0)
|
||||
{
|
||||
printf("Unhandled mailbox response 0x%x\n", MbxHdr->mbxtype);
|
||||
}
|
||||
osal_usleep(1 * 1000 * 1000);
|
||||
}
|
||||
}
|
||||
|
||||
void test_eoe(ecx_contextt * context)
|
||||
{
|
||||
/* Set the HOOK */
|
||||
ecx_EOEdefinehook(context, eoe_hook);
|
||||
|
||||
eoe_param_t ipsettings, re_ipsettings;
|
||||
memset(&ipsettings, 0, sizeof(ipsettings));
|
||||
memset(&re_ipsettings, 0, sizeof(re_ipsettings));
|
||||
|
||||
ipsettings.ip_set = 1;
|
||||
ipsettings.subnet_set = 1;
|
||||
ipsettings.default_gateway_set = 1;
|
||||
|
||||
EOE_IP4_ADDR_TO_U32(&ipsettings.ip, 192, 168, 9, 200);
|
||||
EOE_IP4_ADDR_TO_U32(&ipsettings.subnet, 255, 255, 255, 0);
|
||||
EOE_IP4_ADDR_TO_U32(&ipsettings.default_gateway, 0, 0, 0, 0);
|
||||
|
||||
/* Send a set IP request */
|
||||
ecx_EOEsetIp(context, 1, 0, &ipsettings, EC_TIMEOUTRXM);
|
||||
|
||||
/* Send a get IP request, should return the expected IP back */
|
||||
ecx_EOEgetIp(context, 1, 0, &re_ipsettings, EC_TIMEOUTRXM);
|
||||
|
||||
/* Trigger an MBX read request, to be replaced by slave Mbx
|
||||
* full notification via polling of FMMU status process data
|
||||
*/
|
||||
printf("recieved IP (%d.%d.%d.%d)\n",
|
||||
eoe_ip4_addr1(&re_ipsettings.ip),
|
||||
eoe_ip4_addr2(&re_ipsettings.ip),
|
||||
eoe_ip4_addr3(&re_ipsettings.ip),
|
||||
eoe_ip4_addr4(&re_ipsettings.ip));
|
||||
printf("recieved subnet (%d.%d.%d.%d)\n",
|
||||
eoe_ip4_addr1(&re_ipsettings.subnet),
|
||||
eoe_ip4_addr2(&re_ipsettings.subnet),
|
||||
eoe_ip4_addr3(&re_ipsettings.subnet),
|
||||
eoe_ip4_addr4(&re_ipsettings.subnet));
|
||||
printf("recieved gateway (%d.%d.%d.%d)\n",
|
||||
eoe_ip4_addr1(&re_ipsettings.default_gateway),
|
||||
eoe_ip4_addr2(&re_ipsettings.default_gateway),
|
||||
eoe_ip4_addr3(&re_ipsettings.default_gateway),
|
||||
eoe_ip4_addr4(&re_ipsettings.default_gateway));
|
||||
|
||||
/* Create a asyncronous EoE reader */
|
||||
osal_thread_create(&thread2, 128000, &mailbox_reader, &ecx_context);
|
||||
}
|
||||
|
||||
void teststarter(char *ifname)
|
||||
{
|
||||
int i, oloop, iloop, chk;
|
||||
needlf = FALSE;
|
||||
inOP = FALSE;
|
||||
|
||||
printf("Starting eoe test\n");
|
||||
|
||||
/* initialise SOEM, bind socket to ifname */
|
||||
if (ec_init(ifname))
|
||||
{
|
||||
printf("ec_init on %s succeeded.\n",ifname);
|
||||
/* find and auto-config slaves */
|
||||
if ( ec_config_init(FALSE) > 0 )
|
||||
{
|
||||
printf("%d slaves found and configured.\n",ec_slavecount);
|
||||
|
||||
ec_config_map(&IOmap);
|
||||
|
||||
ec_configdc();
|
||||
|
||||
printf("Slaves mapped, state to SAFE_OP.\n");
|
||||
/* wait for all slaves to reach SAFE_OP state */
|
||||
ec_statecheck(0, EC_STATE_SAFE_OP, EC_TIMEOUTSTATE * 4);
|
||||
|
||||
oloop = ec_slave[0].Obytes;
|
||||
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
|
||||
if (oloop > 8) oloop = 8;
|
||||
iloop = ec_slave[0].Ibytes;
|
||||
if ((iloop == 0) && (ec_slave[0].Ibits > 0)) iloop = 1;
|
||||
if (iloop > 8) iloop = 8;
|
||||
|
||||
printf("segments : %d : %d %d %d %d\n",ec_group[0].nsegments ,ec_group[0].IOsegment[0],ec_group[0].IOsegment[1],ec_group[0].IOsegment[2],ec_group[0].IOsegment[3]);
|
||||
|
||||
printf("Request operational state for all slaves\n");
|
||||
expectedWKC = (ec_group[0].outputsWKC * 2) + ec_group[0].inputsWKC;
|
||||
printf("Calculated workcounter %d\n", expectedWKC);
|
||||
ec_slave[0].state = EC_STATE_OPERATIONAL;
|
||||
/* send one valid process data to make outputs in slaves happy*/
|
||||
ec_send_processdata();
|
||||
ec_receive_processdata(EC_TIMEOUTRET);
|
||||
|
||||
/* Simple EoE test */
|
||||
test_eoe(&ecx_context);
|
||||
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
chk = 200;
|
||||
/* wait for all slaves to reach OP state */
|
||||
do
|
||||
{
|
||||
ec_send_processdata();
|
||||
ec_receive_processdata(EC_TIMEOUTRET);
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, 50000);
|
||||
}
|
||||
while (chk-- && (ec_slave[0].state != EC_STATE_OPERATIONAL));
|
||||
if (ec_slave[0].state == EC_STATE_OPERATIONAL )
|
||||
{
|
||||
printf("Operational state reached for all slaves.\n");
|
||||
globalwkc = expectedWKC;
|
||||
inOP = TRUE;
|
||||
/* cyclic loop */
|
||||
for(i = 1; i <= 10000; i++)
|
||||
{
|
||||
ec_send_processdata();
|
||||
globalwkc = ec_receive_processdata(EC_TIMEOUTRET * 5);
|
||||
#if PRINT_EOE_INFO_INSTEAD
|
||||
int j;
|
||||
if(globalwkc >= expectedWKC)
|
||||
{
|
||||
printf("Processdata cycle %4d, WKC %d , O:", i, globalwkc);
|
||||
for(j = 0 ; j < oloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].outputs + j));
|
||||
}
|
||||
printf(" I:");
|
||||
for(j = 0 ; j < iloop; j++)
|
||||
{
|
||||
printf(" %2.2x", *(ec_slave[0].inputs + j));
|
||||
}
|
||||
printf(" T:%"PRId64"\r",ec_DCtime);
|
||||
needlf = TRUE;
|
||||
}
|
||||
#endif
|
||||
osal_usleep(1000);
|
||||
}
|
||||
inOP = FALSE;
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Not all slaves reached operational state.\n");
|
||||
ec_readstate();
|
||||
for(i = 1; i<=ec_slavecount ; i++)
|
||||
{
|
||||
if(ec_slave[i].state != EC_STATE_OPERATIONAL)
|
||||
{
|
||||
printf("Slave %d State=0x%2.2x StatusCode=0x%4.4x : %s\n",
|
||||
i, ec_slave[i].state, ec_slave[i].ALstatuscode, ec_ALstatuscode2string(ec_slave[i].ALstatuscode));
|
||||
}
|
||||
}
|
||||
}
|
||||
printf("\nRequest init state for all slaves\n");
|
||||
ec_slave[0].state = EC_STATE_INIT;
|
||||
/* request INIT state for all slaves */
|
||||
ec_writestate(0);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("No slaves found!\n");
|
||||
}
|
||||
printf("End eoe test, close socket\n");
|
||||
/* stop SOEM, close socket */
|
||||
ec_close();
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
|
||||
OSAL_THREAD_FUNC ecatcheck( void *ptr )
|
||||
{
|
||||
int slave;
|
||||
(void)ptr; /* Not used */
|
||||
|
||||
while(1)
|
||||
{
|
||||
if( inOP && ((globalwkc < expectedWKC) || ec_group[currentgroup].docheckstate))
|
||||
{
|
||||
if (globalwkc < expectedWKC)
|
||||
{
|
||||
printf("(wkc < expectedWKC) , globalwkc %d\n", globalwkc);
|
||||
}
|
||||
if (ec_group[currentgroup].docheckstate)
|
||||
{
|
||||
printf("(ec_group[currentgroup].docheckstate)\n");
|
||||
}
|
||||
|
||||
if (needlf)
|
||||
{
|
||||
needlf = FALSE;
|
||||
printf("\n");
|
||||
}
|
||||
/* one ore more slaves are not responding */
|
||||
ec_group[currentgroup].docheckstate = FALSE;
|
||||
ec_readstate();
|
||||
for (slave = 1; slave <= ec_slavecount; slave++)
|
||||
{
|
||||
if ((ec_slave[slave].group == currentgroup) && (ec_slave[slave].state != EC_STATE_OPERATIONAL))
|
||||
{
|
||||
ec_group[currentgroup].docheckstate = TRUE;
|
||||
if (ec_slave[slave].state == (EC_STATE_SAFE_OP + EC_STATE_ERROR))
|
||||
{
|
||||
printf("ERROR : slave %d is in SAFE_OP + ERROR, attempting ack.\n", slave);
|
||||
ec_slave[slave].state = (EC_STATE_SAFE_OP + EC_STATE_ACK);
|
||||
ec_writestate(slave);
|
||||
}
|
||||
else if(ec_slave[slave].state == EC_STATE_SAFE_OP)
|
||||
{
|
||||
printf("WARNING : slave %d is in SAFE_OP, change to OPERATIONAL.\n", slave);
|
||||
ec_slave[slave].state = EC_STATE_OPERATIONAL;
|
||||
ec_writestate(slave);
|
||||
}
|
||||
else if(ec_slave[slave].state > EC_STATE_NONE)
|
||||
{
|
||||
if (ec_reconfig_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d reconfigured\n",slave);
|
||||
}
|
||||
}
|
||||
else if(!ec_slave[slave].islost)
|
||||
{
|
||||
/* re-check state */
|
||||
ec_statecheck(slave, EC_STATE_OPERATIONAL, EC_TIMEOUTRET);
|
||||
if (ec_slave[slave].state == EC_STATE_NONE)
|
||||
{
|
||||
ec_slave[slave].islost = TRUE;
|
||||
printf("ERROR : slave %d lost\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (ec_slave[slave].islost)
|
||||
{
|
||||
if(ec_slave[slave].state == EC_STATE_NONE)
|
||||
{
|
||||
if (ec_recover_slave(slave, EC_TIMEOUTMON))
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d recovered\n",slave);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
ec_slave[slave].islost = FALSE;
|
||||
printf("MESSAGE : slave %d found\n",slave);
|
||||
}
|
||||
}
|
||||
}
|
||||
if(!ec_group[currentgroup].docheckstate)
|
||||
printf("OK : all slaves resumed OPERATIONAL.\n");
|
||||
}
|
||||
osal_usleep(10000);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
printf("SOEM (Simple Open EtherCAT Master)\nEoE test\n");
|
||||
|
||||
if (argc > 1)
|
||||
{
|
||||
/* create thread to handle slave error handling in OP */
|
||||
// pthread_create( &thread1, NULL, (void *) &ecatcheck, (void*) &ctime);
|
||||
osal_thread_create(&thread1, 128000, &ecatcheck, (void*) &ctime);
|
||||
|
||||
/* start cyclic part */
|
||||
teststarter(argv[1]);
|
||||
}
|
||||
else
|
||||
{
|
||||
printf("Usage: eoe_test ifname1\nifname = eth0 for example\n");
|
||||
}
|
||||
|
||||
printf("End program\n");
|
||||
return (0);
|
||||
}
|
|
@ -91,7 +91,7 @@ void redtest(char *ifname, char *ifname2)
|
|||
/* activate cyclic process data */
|
||||
dorun = 1;
|
||||
/* wait for all slaves to reach OP state */
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
|
||||
oloop = ec_slave[0].Obytes;
|
||||
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
|
||||
if (oloop > 8) oloop = 8;
|
||||
|
@ -164,7 +164,7 @@ void add_timespec(struct timespec *ts, int64 addtime)
|
|||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
if ( ts->tv_nsec >= NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
|
|
|
@ -70,7 +70,7 @@ void simpletest(char *ifname)
|
|||
ec_receive_processdata(EC_TIMEOUTRET);
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
chk = 40;
|
||||
chk = 200;
|
||||
/* wait for all slaves to reach OP state */
|
||||
do
|
||||
{
|
||||
|
@ -139,7 +139,7 @@ void simpletest(char *ifname)
|
|||
}
|
||||
else
|
||||
{
|
||||
printf("No socket connection on %s\nExcecute as root\n",ifname);
|
||||
printf("No socket connection on %s\nExecute as root\n",ifname);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -233,7 +233,7 @@ int si_PDOassign(uint16 slave, uint16 PDOassign, int mapoffset, int bitoffset)
|
|||
/* read PDO assign */
|
||||
wkc = ec_SDOread(slave, PDOassign, (uint8)idxloop, FALSE, &rdl, &rdat, EC_TIMEOUTRXM);
|
||||
/* result is index of PDO */
|
||||
idx = etohl(rdat);
|
||||
idx = etohs(rdat);
|
||||
if (idx > 0)
|
||||
{
|
||||
rdl = sizeof(subcnt); subcnt = 0;
|
||||
|
@ -558,14 +558,14 @@ void slaveinfo(char *ifname)
|
|||
for(nSM = 0 ; nSM < EC_MAXSM ; nSM++)
|
||||
{
|
||||
if(ec_slave[cnt].SM[nSM].StartAddr > 0)
|
||||
printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, ec_slave[cnt].SM[nSM].StartAddr, ec_slave[cnt].SM[nSM].SMlength,
|
||||
(int)ec_slave[cnt].SM[nSM].SMflags, ec_slave[cnt].SMtype[nSM]);
|
||||
printf(" SM%1d A:%4.4x L:%4d F:%8.8x Type:%d\n",nSM, etohs(ec_slave[cnt].SM[nSM].StartAddr), etohs(ec_slave[cnt].SM[nSM].SMlength),
|
||||
etohl(ec_slave[cnt].SM[nSM].SMflags), ec_slave[cnt].SMtype[nSM]);
|
||||
}
|
||||
for(j = 0 ; j < ec_slave[cnt].FMMUunused ; j++)
|
||||
{
|
||||
printf(" FMMU%1d Ls:%8.8x Ll:%4d Lsb:%d Leb:%d Ps:%4.4x Psb:%d Ty:%2.2x Act:%2.2x\n", j,
|
||||
(int)ec_slave[cnt].FMMU[j].LogStart, ec_slave[cnt].FMMU[j].LogLength, ec_slave[cnt].FMMU[j].LogStartbit,
|
||||
ec_slave[cnt].FMMU[j].LogEndbit, ec_slave[cnt].FMMU[j].PhysStart, ec_slave[cnt].FMMU[j].PhysStartBit,
|
||||
etohl(ec_slave[cnt].FMMU[j].LogStart), etohs(ec_slave[cnt].FMMU[j].LogLength), ec_slave[cnt].FMMU[j].LogStartbit,
|
||||
ec_slave[cnt].FMMU[j].LogEndbit, etohs(ec_slave[cnt].FMMU[j].PhysStart), ec_slave[cnt].FMMU[j].PhysStartBit,
|
||||
ec_slave[cnt].FMMU[j].FMMUtype, ec_slave[cnt].FMMU[j].FMMUactive);
|
||||
}
|
||||
printf(" FMMUfunc 0:%d 1:%d 2:%d 3:%d\n",
|
||||
|
|
|
@ -81,7 +81,7 @@ void redtest(char *ifname, char *ifname2)
|
|||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
/* wait for all slaves to reach OP state */
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, EC_TIMEOUTSTATE);
|
||||
ec_statecheck(0, EC_STATE_OPERATIONAL, 5 * EC_TIMEOUTSTATE);
|
||||
oloop = ec_slave[0].Obytes;
|
||||
if ((oloop == 0) && (ec_slave[0].Obits > 0)) oloop = 1;
|
||||
if (oloop > 8) oloop = 8;
|
||||
|
@ -142,7 +142,7 @@ void add_timespec(struct timespec *ts, int64 addtime)
|
|||
sec = (addtime - nsec) / NSEC_PER_SEC;
|
||||
ts->tv_sec += sec;
|
||||
ts->tv_nsec += nsec;
|
||||
if ( ts->tv_nsec > NSEC_PER_SEC )
|
||||
if ( ts->tv_nsec >= NSEC_PER_SEC )
|
||||
{
|
||||
nsec = ts->tv_nsec % NSEC_PER_SEC;
|
||||
ts->tv_sec += (ts->tv_nsec - nsec) / NSEC_PER_SEC;
|
||||
|
|
|
@ -186,7 +186,7 @@ void simpletest(char *ifname)
|
|||
|
||||
/* request OP state for all slaves */
|
||||
ec_writestate(0);
|
||||
chk = 40;
|
||||
chk = 200;
|
||||
/* wait for all slaves to reach OP state */
|
||||
do
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue