Generic EtherCAT Slave configuration
Configuration options
The GenericEcSlave
allows to configure the following options in the slave_config
file:
Configuration flag |
Description |
---|---|
|
Vendor identification number in hexadecimal format |
|
Product identification number in hexadecimal format |
|
Distributed Clock Synchronization register in hexadecimal format |
|
SDO data to be transferred at drive startup for configuration purposes. |
|
Transmit PDO mapping configuration. |
|
Receive PDO mapping configuration. |
|
Sync Manager configuration. |
SDO configuration
Service Data Objects (SDO) are used to setup the module at startup. This is done only one during the activation phase. Each SDO has the following configuration flags:
SDO flag |
Description |
---|---|
|
SDO index in hexadecimal format |
|
SDO sub-index in hexadecimal format |
|
SDO data type. Possible types: |
|
Value to be transferred to the module. |
PDO mapping configuration
The tpdo
and rpdo
Process Data Object (PDO) mapping configurations can be composed of multiple PDO mappings.
Each PDO mapping requires to specify its register index
and the configuration of the PDO Channels it is composed of.
PDO channel configuration
Each PDO Channel has the following configuration flags:
PDO Channel flag |
Description |
---|---|
|
Channel index in hexadecimal format |
|
Channel sub-index in hexadecimal format |
|
Channel data type. Possible types: |
|
Only for |
|
Only for |
|
Only for |
|
Data mask, to be used with |
|
Data conversion factor/scale ( |
|
Data offset term ( |
Warning
For each channel, tags index
, sub_index
and type
are mandatory even if the channel is not used in order to fill the data layout expected by the module. All other tags can remain unset.
Note
Data type bitN
is used for gaps in the config. Refer to module manual if required.
Note
Data type bool
requires the use of the mask
option as the registers can only be read as a multiple of 8 bits.
Note
Data (d) can be modified using the optional
factor
(f) andoffset
(o) parameters following a linear relation: \(d \longrightarrow f\times d + o\). Default value are \(f=1\) and \(o=0\). It is particularly useful for:
scaling analog values to physical units,
take into account calibration offsets,
convert between different units,
take into account transmission parameters like gear reduction or screw lead for motor control.
Sync Manager Configuration
A SyncManager protects a DPRAM area from simultaneous access and thus ensures data consistency. For more information, refer to the Synch Manager EtherCAT documentation. Sync Manager can be configured with the following options:
Sync Manager flag |
Description |
---|---|
|
Sync Manager index. |
|
Sync Manager type. Can be either |
|
PDO to be mapped on the Sync Manager. Can be |
|
Enables Sync Manager Watchdog. Can be |
Note
If sm
is not specified, the default Sync Manager configuration is :
sm: # Sync Manager
- {index: 0, type: output, pdo: ~, watchdog: disable}
- {index: 1, type: input, pdo: ~, watchdog: disable}
- {index: 2, type: output, pdo: rpdo, watchdog: enable}
- {index: 3, type: input, pdo: tpdo, watchdog: disable}
Usage
Example configuration for the Beckhoff EL3104 analog input module:
# Configuration file for Beckhoff EL3104
vendor_id: 0x00000002
product_id: 0x0c1e3052
tpdo: # TxPDO
- index: 0x1a00
channels:
- {index: 0x3101, sub_index: 1, type: uint8}
- {
index: 0x3101,
sub_index: 2,
type: int16,
state_interface: analog_input.1,
factor: 0.000305185
}
- index: 0x1a01
channels:
- {index: 0x3102, sub_index: 1, type: uint8}
- {
index: 0x3102,
sub_index: 2,
type: int16,
state_interface: analog_input.2,
factor: 0.000305185
}
sm: # Sync Manager
- {index: 0, type: output, pdo: ~, watchdog: disable}
- {index: 1, type: input, pdo: ~, watchdog: disable}
- {index: 2, type: output, pdo: ~, watchdog: disable}
- {index: 3, type: input, pdo: tpdo, watchdog: disable}
Example configuration for the Beckhoff EL2008 digital output module using data type bool
with mask
:
# Configuration file for Beckhoff EL2008
vendor_id: 0x00000002
product_id: 0x07d83052
rpdo: # RxPDO
- index: 0x1a00
channels:
- {index: 0x6000, sub_index: 1, type: bool, mask: 1, command_interface: d_output.1}
- index: 0x1a01
channels:
- {index: 0x6010, sub_index: 1, type: bool}
- index: 0x1a02
channels:
- {index: 0x6020, sub_index: 1, type: bool}
- index: 0x1a03
channels:
- {index: 0x6030, sub_index: 1, type: bool, mask: 8, command_interface: d_output.4}
- index: 0x1a04
channels:
- {index: 0x6040, sub_index: 1, type: bool}
- index: 0x1a05
channels:
- {index: 0x6050, sub_index: 1, type: bool}
- index: 0x1a06
channels:
- {index: 0x6060, sub_index: 1, type: bool}
- index: 0x1a07
channels:
- {index: 0x6070, sub_index: 1, type: bool}
sm: # Sync Manager
- {index: 0, type: output, pdo: rpdo, watchdog: enable}
Note
In this configuration only digital output 1 and 4 will be used and are therefore configured. The other channels are set up with the mandatory tags index
, sub_index
and type
to fill the data layout expected by the module.
This configuration can be used for controlling a gpio
component. Here is an example urdf for ros2_control
using this configuration together with the GenericEcSlave
plugin:
<ros2_control name="ec_single_gpio" type="system">
<hardware>
<plugin>ethercat_driver/EthercatDriver</plugin>
<param name="master_id">0</param>
<param name="control_frequency">100</param>
</hardware>
<gpio name="gpio_0">
<state_interface name="analog_input.1"/>
<state_interface name="analog_input.2"/>
<ec_module name="EL3104">
<plugin>ethercat_generic_plugins/GenericEcSlave</plugin>
<param name="alias">0</param>
<param name="position">0</param>
<param name="slave_config">/path/to/EL3104_slave_config.yaml</param>
</ec_module>
</gpio>
<gpio name="gpio_1">
<command_interface name="d_output.1"/>
<command_interface name="d_output.4"/>
<ec_module name="EL2008">
<plugin>ethercat_generic_plugins/GenericEcSlave</plugin>
<param name="alias">0</param>
<param name="position">1</param>
<param name="slave_config">/path/to/EL2008_slave_config.yaml</param>
</ec_module>
</gpio>
</ros2_control>